PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
goto.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 <optional>
10 #include <px4_msgs/msg/goto_setpoint.hpp>
11 #include <px4_ros2/common/setpoint_base.hpp>
12 #include <px4_ros2/utils/geodesic.hpp>
13 
14 namespace px4_ros2 {
23  public:
24  explicit MulticopterGotoSetpointType(Context& context);
25 
26  ~MulticopterGotoSetpointType() override = default;
27 
28  Configuration getConfiguration() override;
29 
41  void update(const Eigen::Vector3f& position, const std::optional<float>& heading = {},
42  const std::optional<float>& max_horizontal_speed = {},
43  const std::optional<float>& max_vertical_speed = {},
44  const std::optional<float>& max_heading_rate = {});
45 
46  float desiredUpdateRateHz() override { return 30.f; }
47 
48  private:
49  rclcpp::Node& _node;
50  rclcpp::Publisher<px4_msgs::msg::GotoSetpoint>::SharedPtr _goto_setpoint_pub;
51 };
52 
57  public:
58  explicit MulticopterGotoGlobalSetpointType(Context& context);
59 
61 
73  void update(const Eigen::Vector3d& global_position, const std::optional<float>& heading = {},
74  const std::optional<float>& max_horizontal_speed = {},
75  const std::optional<float>& max_vertical_speed = {},
76  const std::optional<float>& max_heading_rate = {});
77 
78  private:
79  rclcpp::Node& _node;
80  std::unique_ptr<MapProjection> _map_projection;
81  std::shared_ptr<MulticopterGotoSetpointType> _goto_setpoint;
82 };
83 
85 } /* namespace px4_ros2 */
Definition: context.hpp:18
Setpoint type for smooth global position and heading control.
Definition: goto.hpp:56
void update(const Eigen::Vector3d &global_position, const std::optional< float > &heading={}, const std::optional< float > &max_horizontal_speed={}, const std::optional< float > &max_vertical_speed={}, const std::optional< float > &max_heading_rate={})
Go-to global setpoint update.
Setpoint type for smooth position and heading control.
Definition: goto.hpp:22
void update(const Eigen::Vector3f &position, const std::optional< float > &heading={}, const std::optional< float > &max_horizontal_speed={}, const std::optional< float > &max_vertical_speed={}, const std::optional< float > &max_heading_rate={})
Go-to setpoint update.
Definition: setpoint_base.hpp:19
Definition: setpoint_base.hpp:23