PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
speed_steering.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_speed_setpoint.hpp>
9
#include <px4_msgs/msg/rover_steering_setpoint.hpp>
10
11
#include <px4_ros2/common/setpoint_base.hpp>
12
13
namespace
px4_ros2
14
{
22
class
RoverSpeedSteeringSetpointType
:
public
SetpointBase
23
{
24
public
:
25
explicit
RoverSpeedSteeringSetpointType
(
Context
& context);
26
27
~
RoverSpeedSteeringSetpointType
()
override
=
default
;
28
29
Configuration
getConfiguration()
override
;
30
float
desiredUpdateRateHz()
override
{
return
30.f;}
31
39
void
update
(
40
float
speed_body_x,
float
normalized_steering_setpoint,
41
std::optional<float> speed_body_y = {});
42
43
private
:
44
rclcpp::Node & _node;
45
rclcpp::Publisher<px4_msgs::msg::RoverSpeedSetpoint>::SharedPtr
46
_rover_speed_setpoint_pub;
47
rclcpp::Publisher<px4_msgs::msg::RoverSteeringSetpoint>::SharedPtr
48
_rover_steering_setpoint_pub;
49
};
50
52
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition:
context.hpp:20
px4_ros2::RoverSpeedSteeringSetpointType
Setpoint type for rover speed and steering control.
Definition:
speed_steering.hpp:23
px4_ros2::RoverSpeedSteeringSetpointType::update
void update(float speed_body_x, float normalized_steering_setpoint, std::optional< float > speed_body_y={})
Send a rover speed setpoint and a rover steering setpoint to the flight controller.
px4_ros2::SetpointBase
Definition:
setpoint_base.hpp:20
px4_ros2::SetpointBase::Configuration
Definition:
setpoint_base.hpp:25
px4_ros2_cpp
include
px4_ros2
control
setpoint_types
experimental
rover
speed_steering.hpp
Generated by
1.9.1