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 <Eigen/Eigen>
9 #include <px4_msgs/msg/rover_position_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
21  public:
22  explicit RoverPositionSetpointType(Context& context);
23 
24  ~RoverPositionSetpointType() override = default;
25 
26  Configuration getConfiguration() override;
27  float desiredUpdateRateHz() override { return 30.f; }
28 
42  void update(const Eigen::Vector2f& position_ned,
43  const std::optional<Eigen::Vector2f>& start_ned = {},
44  std::optional<float> cruising_speed = {}, std::optional<float> arrival_speed = {},
45  std::optional<float> yaw = {});
46 
47  private:
48  rclcpp::Node& _node;
49  rclcpp::Publisher<px4_msgs::msg::RoverPositionSetpoint>::SharedPtr _rover_position_setpoint_pub;
50 };
51 
53 } /* namespace px4_ros2 */
Definition: context.hpp:18
Setpoint type for rover position control.
Definition: position.hpp:20
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:19
Definition: setpoint_base.hpp:23