PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
trajectory.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/trajectory_setpoint.hpp>
9 #include <Eigen/Eigen>
10 
11 #include <px4_ros2/common/setpoint_base.hpp>
12 
13 namespace px4_ros2
14 {
25 {
26 public:
27  explicit TrajectorySetpointType(Context & context);
28 
29  ~TrajectorySetpointType() override = default;
30 
31  Configuration getConfiguration() override;
32 
33  void update(
34  const Eigen::Vector3f & velocity_ned_m_s,
35  const std::optional<Eigen::Vector3f> & acceleration_ned_m_s2 = {},
36  std::optional<float> yaw_ned_rad = {},
37  std::optional<float> yaw_rate_ned_rad_s = {});
38 
47  const Eigen::Vector3f & position_ned_m);
48 
49 private:
50  rclcpp::Node & _node;
51  rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr _trajectory_setpoint_pub;
52 };
53 
55 } /* namespace px4_ros2 */
Definition: context.hpp:20
Definition: setpoint_base.hpp:20
Setpoint type for trajectory control.
Definition: trajectory.hpp:25
void updatePosition(const Eigen::Vector3f &position_ned_m)
Position setpoint update.
Definition: setpoint_base.hpp:25