Go to the documentation of this file.
21 #include <nav_msgs/Path.h>
22 #include <mavros_msgs/PositionTarget.h>
23 #include <mavros_msgs/SetMavFrame.h>
24 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
25 #include <trajectory_msgs/MultiDOFJointTrajectoryPoint.h>
26 #include <std_srvs/Trigger.h>
29 namespace std_plugins {
30 using mavlink::common::MAV_FRAME;
41 sp_nh(
"~setpoint_trajectory")
46 PluginBase::initialize(uas_);
59 std::string mav_frame_str;
88 std::vector<trajectory_msgs::MultiDOFJointTrajectoryPoint>::const_iterator
setpoint_target;
106 for (
const auto &p : req->points) {
107 if (p.transforms.empty())
110 geometry_msgs::PoseStamped pose_msg;
111 pose_msg.pose.position.x = p.transforms[0].translation.x;
112 pose_msg.pose.position.y = p.transforms[0].translation.y;
113 pose_msg.pose.position.z = p.transforms[0].translation.z;
114 pose_msg.pose.orientation = p.transforms[0].rotation;
115 msg.poses.emplace_back(pose_msg);
126 if(
static_cast<MAV_FRAME
>(
mav_frame) == MAV_FRAME::BODY_NED ||
static_cast<MAV_FRAME
>(
mav_frame) == MAV_FRAME::BODY_OFFSET_NED){
142 using mavlink::common::POSITION_TARGET_TYPEMASK;
148 Eigen::Vector3d position, velocity, af;
149 Eigen::Quaterniond attitude = Eigen::Quaterniond::Identity();
151 float yaw_rate = 0.f;
152 uint16_t type_mask = 0;
158 type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::X_IGNORE)
159 | uint16_t(POSITION_TARGET_TYPEMASK::Y_IGNORE)
160 | uint16_t(POSITION_TARGET_TYPEMASK::Z_IGNORE)
161 | uint16_t(POSITION_TARGET_TYPEMASK::YAW_IGNORE);
170 type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::VX_IGNORE)
171 | uint16_t(POSITION_TARGET_TYPEMASK::VY_IGNORE)
172 | uint16_t(POSITION_TARGET_TYPEMASK::VZ_IGNORE)
173 | uint16_t(POSITION_TARGET_TYPEMASK::YAW_RATE_IGNORE);
181 type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::AX_IGNORE)
182 | uint16_t(POSITION_TARGET_TYPEMASK::AY_IGNORE)
183 | uint16_t(POSITION_TARGET_TYPEMASK::AZ_IGNORE);
208 bool reset_cb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
215 res.message =
"Trajectory reset denied: Empty trajectory";
221 bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
223 mav_frame =
static_cast<MAV_FRAME
>(req.mav_frame);
trajectory_msgs::MultiDOFJointTrajectory::ConstPtr trajectory_target_msg
void setParam(const std::string &key, bool b) const
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
friend class SetPositionTargetLocalNEDMixin
double quaternion_get_yaw(const Eigen::Quaterniond &q)
Get Yaw angle from quaternion.
ros::Subscriber local_sub
PluginBase()
Plugin constructor Should not do anything before initialize()
bool getParam(const std::string &key, bool &b) const
std::vector< trajectory_msgs::MultiDOFJointTrajectoryPoint >::const_iterator setpoint_target
void set_position_target_local_ned(uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, Eigen::Vector3d p, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED.
void publish_path(const trajectory_msgs::MultiDOFJointTrajectory::ConstPtr &req)
std::recursive_mutex mutex
std::shared_ptr< MAVConnInterface const > ConstPtr
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void reset_timer(ros::Duration duration)
void publish(const boost::shared_ptr< M > &message) const
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
Publisher advertise(AdvertiseOptions &ops)
void local_cb(const trajectory_msgs::MultiDOFJointTrajectory::ConstPtr &req)
@ BASELINK_TO_AIRCRAFT
change from expressed WRT baselnk to WRT aircraft
void initialize(UAS &uas_) override
Plugin initializer.
void reference_cb(const ros::TimerEvent &event)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setPeriod(const Duration &period, bool reset=true)
std::string to_string(timesync_mode e)
ros::ServiceServer mav_frame_srv
bool reset_cb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
SetpointTrajectoryPlugin()
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
Transform data expressed in one frame to another frame.
This mixin adds set_position_target_local_ned()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
@ ENU_TO_NED
change from expressed WRT ENU frame to WRT NED frame
Mixin for setpoint plugins.
Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const StaticTF transform)
Transform representation of attitude from 1 frame to another (e.g. transfrom attitude from representi...
Setpoint TRAJECTORY plugin.
bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
MAVROS Plugin base class.
T param(const std::string ¶m_name, const T &default_val) const
std::vector< trajectory_msgs::MultiDOFJointTrajectoryPoint >::const_iterator next_setpoint_target
ros::ServiceServer trajectory_reset_srv
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
constexpr std::underlying_type< _T >::type enum_value(_T e)
std::lock_guard< std::mutex > lock_guard
ros::Publisher desired_pub
StaticTF
Orientation transform options when applying rotations to data.
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03