PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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 <Eigen/Core>
9
#include <px4_msgs/msg/vehicle_command.hpp>
10
#include <px4_ros2/common/setpoint_base.hpp>
11
12
namespace
px4_ros2 {
23
class
PeripheralActuatorControls
{
24
public
:
25
static
constexpr
int
kNumActuators = 6;
26
27
explicit
PeripheralActuatorControls
(
Context
& context);
28
33
void
set
(
const
Eigen::Matrix<float, kNumActuators, 1>& values);
34
40
void
set
(
float
value,
unsigned
index = 0);
41
42
private
:
43
rclcpp::Node& _node;
44
rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
45
rclcpp::Time _last_update{};
46
};
47
49
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition
context.hpp:18
px4_ros2::PeripheralActuatorControls
Provides control of one or more extra actuators.
Definition
peripheral_actuators.hpp:23
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.8