PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
peripheral_actuators.hpp
1
/****************************************************************************
2
* Copyright (c) 2023 PX4 Development Team.
3
* SPDX-License-Identifier: BSD-3-Clause
4
****************************************************************************/
5
6
#pragma once
7
8
#include <px4_msgs/msg/vehicle_command.hpp>
9
#include <Eigen/Core>
10
11
#include <px4_ros2/common/setpoint_base.hpp>
12
13
namespace
px4_ros2
14
{
25
class
PeripheralActuatorControls
26
{
27
public
:
28
static
constexpr
int
kNumActuators = 6;
29
30
explicit
PeripheralActuatorControls
(
Context
& context);
31
36
void
set
(
const
Eigen::Matrix<float, kNumActuators, 1> & values);
37
43
void
set
(
float
value,
unsigned
index = 0);
44
45
private
:
46
rclcpp::Node & _node;
47
rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
48
rclcpp::Time _last_update{};
49
};
50
52
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition:
context.hpp:20
px4_ros2::PeripheralActuatorControls
Provides control of one or more extra actuators.
Definition:
peripheral_actuators.hpp:26
px4_ros2::PeripheralActuatorControls::set
void set(float value, unsigned index=0)
px4_ros2::PeripheralActuatorControls::set
void set(const Eigen::Matrix< float, kNumActuators, 1 > &values)
px4_ros2_cpp
include
px4_ros2
control
peripheral_actuators.hpp
Generated by
1.9.1