PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
throttle_rate.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/rover_rate_setpoint.hpp>
9
#include <px4_msgs/msg/rover_throttle_setpoint.hpp>
10
#include <px4_ros2/common/setpoint_base.hpp>
11
12
namespace
px4_ros2 {
20
class
RoverThrottleRateSetpointType
:
public
SetpointBase
{
21
public
:
22
explicit
RoverThrottleRateSetpointType
(
Context
& context);
23
24
~RoverThrottleRateSetpointType
()
override
=
default
;
25
26
Configuration
getConfiguration()
override
;
27
float
desiredUpdateRateHz()
override
{
return
30.f; }
28
38
void
update
(
float
throttle_body_x,
float
yaw_rate_setpoint,
39
std::optional<float> throttle_body_y = {});
40
41
private
:
42
rclcpp::Node& _node;
43
rclcpp::Publisher<px4_msgs::msg::RoverThrottleSetpoint>::SharedPtr _rover_throttle_setpoint_pub;
44
rclcpp::Publisher<px4_msgs::msg::RoverRateSetpoint>::SharedPtr _rover_rate_setpoint_pub;
45
};
46
48
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition
context.hpp:18
px4_ros2::RoverThrottleRateSetpointType
Setpoint type for rover throttle and rate control.
Definition
throttle_rate.hpp:20
px4_ros2::RoverThrottleRateSetpointType::update
void update(float throttle_body_x, float yaw_rate_setpoint, std::optional< float > throttle_body_y={})
Send a rover throttle setpoint and a rover rate setpoint to the flight controller.
px4_ros2::SetpointBase
Definition
setpoint_base.hpp:19
px4_ros2::SetpointBase::Configuration
Definition
setpoint_base.hpp:23
px4_ros2_cpp
include
px4_ros2
control
setpoint_types
experimental
rover
throttle_rate.hpp
Generated by
1.9.8