19#include <px4_msgs/msg/trajectory_setpoint.hpp>
20#include <rclcpp/rclcpp.hpp>
26class CpVehicleLocalPosition;
37 float x,
float y,
float z,
float yaw = std::numeric_limits<float>::quiet_NaN());
44 rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr
publisher_;
void onInitialize() override
px4_msgs::msg::TrajectorySetpoint getLastSetpoint() const
px4_msgs::msg::TrajectorySetpoint lastSetpoint_
virtual ~CpTrajectorySetpoint()
void setPositionNED(float x, float y, float z, float yaw=std::numeric_limits< float >::quiet_NaN())
rclcpp::Publisher< px4_msgs::msg::TrajectorySetpoint >::SharedPtr publisher_
CpVehicleLocalPosition * localPosition_