PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
position.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_position_setpoint.hpp>
9 #include <Eigen/Eigen>
10 
11 #include <px4_ros2/common/setpoint_base.hpp>
12 
13 namespace px4_ros2
14 {
23 {
24 public:
25  explicit RoverPositionSetpointType(Context & context);
26 
27  ~RoverPositionSetpointType() override = default;
28 
29  Configuration getConfiguration() override;
30  float desiredUpdateRateHz() override {return 30.f;}
31 
41  void update(
42  const Eigen::Vector2f & position_ned, const std::optional<Eigen::Vector2f> & start_ned = {},
43  std::optional<float> cruising_speed = {}, std::optional<float> arrival_speed = {},
44  std::optional<float> yaw = {});
45 
46 private:
47  rclcpp::Node & _node;
48  rclcpp::Publisher<px4_msgs::msg::RoverPositionSetpoint>::SharedPtr
49  _rover_position_setpoint_pub;
50 };
51 
53 } /* namespace px4_ros2 */
Definition: context.hpp:20
Setpoint type for rover position control.
Definition: position.hpp:23
void update(const Eigen::Vector2f &position_ned, const std::optional< Eigen::Vector2f > &start_ned={}, std::optional< float > cruising_speed={}, std::optional< float > arrival_speed={}, std::optional< float > yaw={})
Send a rover position setpoint to the flight controller.
Definition: setpoint_base.hpp:20
Definition: setpoint_base.hpp:25