setpoint_trajectory.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2019 Jaeyoung Lim.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include <mavros/setpoint_mixin.h>
20 
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>
27 
28 namespace mavros {
29 namespace std_plugins {
30 using mavlink::common::MAV_FRAME;
31 
38  private plugin::SetPositionTargetLocalNEDMixin<SetpointTrajectoryPlugin> {
39 public:
41  sp_nh("~setpoint_trajectory")
42  { }
43 
44  void initialize(UAS &uas_) override
45  {
46  PluginBase::initialize(uas_);
47 
48  sp_nh.param<std::string>("frame_id", frame_id, "map");
49 
51  desired_pub = sp_nh.advertise<nav_msgs::Path>("desired", 10);
52 
55 
57 
58  // mav_frame
59  std::string mav_frame_str;
60  if (!sp_nh.getParam("mav_frame", mav_frame_str)) {
61  mav_frame = MAV_FRAME::LOCAL_NED;
62  } else {
63  mav_frame = utils::mav_frame_from_str(mav_frame_str);
64  }
65  }
66 
68  {
69  return { /* Rx disabled */ };
70  }
71 
72 private:
74  using lock_guard = std::lock_guard<std::mutex>;
76 
78 
80 
83 
86 
88  std::vector<trajectory_msgs::MultiDOFJointTrajectoryPoint>::const_iterator setpoint_target;
89  std::vector<trajectory_msgs::MultiDOFJointTrajectoryPoint>::const_iterator next_setpoint_target;
90 
91  std::string frame_id;
94 
95  void reset_timer(ros::Duration duration){
96  sp_timer.stop();
97  sp_timer.setPeriod(duration);
98  sp_timer.start();
99  }
100 
102  nav_msgs::Path msg;
103 
104  msg.header.stamp = ros::Time::now();
105  msg.header.frame_id = frame_id;
106  for (const auto &p : req->points) {
107  if (p.transforms.empty())
108  continue;
109 
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);
116  }
117  desired_pub.publish(msg);
118  }
119 
120  /* -*- callbacks -*- */
121 
123  {
124  lock_guard lock(mutex);
125 
126  if(static_cast<MAV_FRAME>(mav_frame) == MAV_FRAME::BODY_NED || static_cast<MAV_FRAME>(mav_frame) == MAV_FRAME::BODY_OFFSET_NED){
128  } else {
129  transform = ftf::StaticTF::ENU_TO_NED;
130  }
131 
132  trajectory_target_msg = req;
133 
134  // Read first duration of the setpoint and set the timer
135  setpoint_target = req->points.cbegin();
136  reset_timer(setpoint_target->time_from_start);
137  publish_path(req);
138  }
139 
140  void reference_cb(const ros::TimerEvent &event)
141  {
142  using mavlink::common::POSITION_TARGET_TYPEMASK;
143  lock_guard lock(mutex);
144 
145  if(!trajectory_target_msg)
146  return;
147 
148  Eigen::Vector3d position, velocity, af;
149  Eigen::Quaterniond attitude;
150  float yaw, yaw_rate;
151  uint16_t type_mask = 0;
152  if(!setpoint_target->transforms.empty()){
153  position = ftf::detail::transform_static_frame(ftf::to_eigen(setpoint_target->transforms[0].translation), transform);
154  attitude = ftf::detail::transform_orientation(ftf::to_eigen(setpoint_target->transforms[0].rotation), transform);
155 
156  } else {
157  type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::X_IGNORE)
158  | uint16_t(POSITION_TARGET_TYPEMASK::Y_IGNORE)
159  | uint16_t(POSITION_TARGET_TYPEMASK::Z_IGNORE)
160  | uint16_t(POSITION_TARGET_TYPEMASK::YAW_IGNORE);
161 
162  }
163 
164  if(!setpoint_target->velocities.empty()){
165  velocity = ftf::detail::transform_static_frame(ftf::to_eigen(setpoint_target->velocities[0].linear), transform);
166  yaw_rate = setpoint_target->velocities[0].angular.z;
167 
168  } else {
169  type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::VX_IGNORE)
170  | uint16_t(POSITION_TARGET_TYPEMASK::VY_IGNORE)
171  | uint16_t(POSITION_TARGET_TYPEMASK::VZ_IGNORE)
172  | uint16_t(POSITION_TARGET_TYPEMASK::YAW_RATE_IGNORE);
173 
174  }
175 
176  if(!setpoint_target->accelerations.empty()){
177  af = ftf::detail::transform_static_frame(ftf::to_eigen(setpoint_target->accelerations[0].linear), transform);
178 
179  } else {
180  type_mask = type_mask | uint16_t(POSITION_TARGET_TYPEMASK::AX_IGNORE)
181  | uint16_t(POSITION_TARGET_TYPEMASK::AY_IGNORE)
182  | uint16_t(POSITION_TARGET_TYPEMASK::AZ_IGNORE);
183 
184  }
185 
187  ros::Time::now().toNSec() / 1000000,
188  utils::enum_value(mav_frame),
189  type_mask,
190  position,
191  velocity,
192  af,
193  ftf::quaternion_get_yaw(attitude),
194  yaw_rate);
195 
196  next_setpoint_target = setpoint_target + 1;
197  if (next_setpoint_target != trajectory_target_msg->points.cend()) {
198  reset_timer(setpoint_target->time_from_start);
199  setpoint_target = next_setpoint_target;
200  } else {
201  trajectory_target_msg.reset();
202  }
203 
204  return;
205  }
206 
207  bool reset_cb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
208  {
209  if(trajectory_target_msg){
210  trajectory_target_msg.reset();
211  res.success = true;
212  } else {
213  res.success = false;
214  res.message = "Trajectory reset denied: Empty trajectory";
215  }
216 
217  return true;
218  }
219 
220  bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
221  {
222  mav_frame = static_cast<MAV_FRAME>(req.mav_frame);
223  const std::string mav_frame_str = utils::to_string(mav_frame);
224  sp_nh.setParam("mav_frame", mav_frame_str);
225  res.success = true;
226  return true;
227  }
228 };
229 } // namespace std_plugins
230 } // namespace mavros
231 
msg
MAVROS Plugin base class.
Definition: mavros_plugin.h:36
void local_cb(const trajectory_msgs::MultiDOFJointTrajectory::ConstPtr &req)
std::shared_ptr< MAVConnInterface const > ConstPtr
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
void publish(const boost::shared_ptr< M > &message) const
trajectory_msgs::MultiDOFJointTrajectory::ConstPtr trajectory_target_msg
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
MAVROS Plugin base.
bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
void stop()
void setPeriod(const Duration &period, bool reset=true)
StaticTF
Orientation transform options when applying rotations to data.
Definition: frame_tf.h:60
void start()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void reference_cb(const ros::TimerEvent &event)
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...
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.
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
Transform data expressed in one frame to another frame.
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:74
std::vector< trajectory_msgs::MultiDOFJointTrajectoryPoint >::const_iterator setpoint_target
void publish_path(const trajectory_msgs::MultiDOFJointTrajectory::ConstPtr &req)
UAS for plugins.
Definition: mavros_uas.h:67
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Mixin for setpoint plugins.
std::string to_string(timesync_mode e)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
Definition: frame_tf.h:452
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
std::vector< trajectory_msgs::MultiDOFJointTrajectoryPoint >::const_iterator next_setpoint_target
bool reset_cb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
This mixin adds set_position_target_local_ned()
change from expressed WRT baselnk to WRT aircraft
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:47
double quaternion_get_yaw(const Eigen::Quaterniond &q)
Get Yaw angle from quaternion.
bool getParam(const std::string &key, std::string &s) const
static Time now()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
change from expressed WRT ENU frame to WRT NED frame
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void initialize(UAS &uas_) override
Plugin initializer.
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
std::recursive_mutex mutex


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:26