8 #include <px4_msgs/msg/rover_position_setpoint.hpp>
11 #include <px4_ros2/common/setpoint_base.hpp>
30 float desiredUpdateRateHz()
override {
return 30.f;}
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 = {});
48 rclcpp::Publisher<px4_msgs::msg::RoverPositionSetpoint>::SharedPtr
49 _rover_position_setpoint_pub;
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