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 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
21  public:
22  explicit RoverSpeedSteeringSetpointType(Context& context);
23 
24  ~RoverSpeedSteeringSetpointType() override = default;
25 
26  Configuration getConfiguration() override;
27  float desiredUpdateRateHz() override { return 30.f; }
28 
40  void update(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 _rover_speed_setpoint_pub;
46  rclcpp::Publisher<px4_msgs::msg::RoverSteeringSetpoint>::SharedPtr _rover_steering_setpoint_pub;
47 };
48 
50 } /* namespace px4_ros2 */
Definition: context.hpp:18
Setpoint type for rover speed and steering control.
Definition: speed_steering.hpp:20
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.
Definition: setpoint_base.hpp:19
Definition: setpoint_base.hpp:23