trajectory.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2018 Martina Rivizzigno.
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.mdA
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include <mavros_msgs/Trajectory.h>
19 #include <mavros_msgs/PositionTarget.h>
20 #include <nav_msgs/Path.h>
21 
22 namespace mavros {
23 namespace extra_plugins {
24 using utils::enum_value;
25 
27 static constexpr size_t NUM_POINTS = 5;
28 
30 using MavPoints = std::array<float, NUM_POINTS>;
31 
32 using RosPoints = mavros_msgs::PositionTarget;
33 
41 public:
43  trajectory_nh("~trajectory")
44  { }
45 
46  void initialize(UAS &uas_)
47  {
49 
52  trajectory_desired_pub = trajectory_nh.advertise<mavros_msgs::Trajectory>("desired", 10);
53  }
54 
56  {
57  return {
59  };
60  }
61 
62 private:
64 
67 
69 
70  // [[[cog:
71  // def outl_fill_points_ned_vector(x, y, z, vec_name, vec_type, point_xyz):
72  // cog.outl(
73  // """void fill_points_{vec_name}(MavPoints &{x}, MavPoints &{y}, MavPoints &{z}, const geometry_msgs::{vec_type} &{vec_name}, const size_t i)\n"""
74  // """{{\n"""
75  // """\tauto {vec_name}_ned = ftf::transform_frame_enu_ned(ftf::to_eigen({vec_name}));\n"""
76  // .format(**locals())
77  // )
78  //
79  // for axis in "xyz":
80  // cog.outl("\t{axis}[i] = {vec_name}_ned.{axis}();".format(**locals()))
81  //
82  // cog.outl("}\n")
83  //
84  //
85  // outl_fill_points_ned_vector('x', 'y', 'z', 'position', 'Point', range(0, 3))
86  // outl_fill_points_ned_vector('x', 'y', 'z', 'velocity', 'Vector3', range(3, 6))
87  // outl_fill_points_ned_vector('x', 'y', 'z', 'acceleration', 'Vector3', range(6, 9))
88  // ]]]
89  void fill_points_position(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Point &position, const size_t i)
90  {
91  auto position_ned = ftf::transform_frame_enu_ned(ftf::to_eigen(position));
92 
93  x[i] = position_ned.x();
94  y[i] = position_ned.y();
95  z[i] = position_ned.z();
96  }
97 
98  void fill_points_velocity(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &velocity, const size_t i)
99  {
100  auto velocity_ned = ftf::transform_frame_enu_ned(ftf::to_eigen(velocity));
101 
102  x[i] = velocity_ned.x();
103  y[i] = velocity_ned.y();
104  z[i] = velocity_ned.z();
105  }
106 
107  void fill_points_acceleration(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &acceleration, const size_t i)
108  {
109  auto acceleration_ned = ftf::transform_frame_enu_ned(ftf::to_eigen(acceleration));
110 
111  x[i] = acceleration_ned.x();
112  y[i] = acceleration_ned.y();
113  z[i] = acceleration_ned.z();
114  }
115 
116  // [[[end]]] (checksum: 92ea0f7f329c90c486fdb8b738c0e7c3)
117 
118 
119  void fill_points_yaw_wp(MavPoints &y, const double yaw, const size_t i) {
120  y[i] = wrap_pi(-yaw + (M_PI / 2.0f));
121  }
122 
123  void fill_points_yaw_speed(MavPoints &yv, const double yaw_speed, const size_t i) {
124  yv[i] = yaw_speed;
125  }
126 
127  void fill_points_yaw_q(MavPoints &y, const geometry_msgs::Quaternion &orientation, const size_t i) {
130  ftf::to_eigen(orientation)));
131  auto yaw_wp = ftf::quaternion_get_yaw(q_wp);
132 
133  y[i] = wrap_pi(-yaw_wp + (M_PI / 2.0f));
134  }
135 
136  auto fill_points_unused_path(mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t, const size_t i) {
137  t.vel_x[i] = NAN;
138  t.vel_y[i] = NAN;
139  t.vel_z[i] = NAN;
140  t.acc_x[i] = NAN;
141  t.acc_y[i] = NAN;
142  t.acc_z[i] = NAN;
143  t.vel_yaw[i] = NAN;
144  }
145 
146  void fill_points_all_unused(mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) {
147  t.pos_x[i] = NAN;
148  t.pos_y[i] = NAN;
149  t.pos_z[i] = NAN;
150 
151  t.vel_x[i] = NAN;
152  t.vel_y[i] = NAN;
153  t.vel_z[i] = NAN;
154 
155  t.acc_x[i] = NAN;
156  t.acc_y[i] = NAN;
157  t.acc_z[i] = NAN;
158 
159  t.pos_yaw[i] = NAN;
160  t.vel_yaw[i] = NAN;
161  }
162 
163 
164  void fill_msg_position(geometry_msgs::Point &position, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
165  {
166  auto position_enu = ftf::transform_frame_ned_enu(Eigen::Vector3d(t.pos_x[i], t.pos_y[i], t.pos_z[i]));
167 
168  position.x = position_enu.x();
169  position.y = position_enu.y();
170  position.z = position_enu.z();
171  }
172 
173  void fill_msg_velocity(geometry_msgs::Vector3 &velocity, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
174  {
175  auto velocity_enu = ftf::transform_frame_ned_enu(Eigen::Vector3d(t.vel_x[i], t.vel_y[i], t.vel_z[i]));
176 
177  velocity.x = velocity_enu.x();
178  velocity.y = velocity_enu.y();
179  velocity.z = velocity_enu.z();
180  }
181 
182  void fill_msg_acceleration(geometry_msgs::Vector3 &acceleration, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
183  {
184  auto acceleration_enu = ftf::transform_frame_ned_enu(Eigen::Vector3d(t.acc_x[i], t.acc_y[i], t.acc_z[i]));
185 
186  acceleration.x = acceleration_enu.x();
187  acceleration.y = acceleration_enu.y();
188  acceleration.z = acceleration_enu.z();
189  }
190 
191 
192  // -*- callbacks -*-
193 
201  {
202  ROS_ASSERT(NUM_POINTS == req->point_valid.size());
203 
204  mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
205 
206  auto fill_point = [&](mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t, const RosPoints &rp, const size_t i) {
207  const auto valid = req->point_valid[i];
208 
209  auto valid_so_far = trajectory.valid_points;
210  if (!valid) {
212  return;
213  }
214 
215  trajectory.valid_points = valid_so_far + 1;
216  fill_points_position(t.pos_x, t.pos_y, t.pos_z, rp.position, i);
217  fill_points_velocity(t.vel_x, t.vel_y, t.vel_z, rp.velocity, i);
218  fill_points_acceleration(t.acc_x, t.acc_y, t.acc_z, rp.acceleration_or_force, i);
219  fill_points_yaw_wp(t.pos_yaw, rp.yaw, i);
220  fill_points_yaw_speed(t.vel_yaw, rp.yaw_rate, i);
221  t.command[i] = UINT16_MAX;
222  };
223 
224  trajectory.time_usec = req->header.stamp.toNSec() / 1000;
225 
226  // [[[cog:
227  // for i in range(5):
228  // cog.outl(
229  // 'fill_point(trajectory, req->point_{i1}, {i0});'
230  // .format(i0=i, i1=i+1)
231  // )
232  // ]]]
233  fill_point(trajectory, req->point_1, 0);
234  fill_point(trajectory, req->point_2, 1);
235  fill_point(trajectory, req->point_3, 2);
236  fill_point(trajectory, req->point_4, 3);
237  fill_point(trajectory, req->point_5, 4);
238  // [[[end]]] (checksum: 16d650d405469f331a17c2f5a892365d)
239 
240  UAS_FCU(m_uas)->send_message_ignore_drop(trajectory);
241  }
242 
243 
251  {
252  mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
253 
254  trajectory.time_usec = req->header.stamp.toNSec() / 1000;
255  trajectory.valid_points = std::min(NUM_POINTS, req->poses.size());
256 
257  auto fill_point = [&](mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t, const size_t i) {
258  t.command[i] = UINT16_MAX;
259  if (req->poses.size() < i + 1) {
261  }
262  else {
263  auto &pose = req->poses[i].pose;
264 
265  fill_points_position(t.pos_x, t.pos_y, t.pos_z, pose.position, i);
266  fill_points_yaw_q(t.pos_yaw, pose.orientation, i);
268  }
269  };
270 
271  // [[[cog:
272  // for i in range(5):
273  // cog.outl(
274  // 'fill_point(trajectory, {i0});'.format(i0=i, i1=i+1))
275  // ]]]
276  fill_point(trajectory, 0);
277  fill_point(trajectory, 1);
278  fill_point(trajectory, 2);
279  fill_point(trajectory, 3);
280  fill_point(trajectory, 4);
281  // [[[end]]] (checksum: 267a911c65a3768f04a8230fcb235bca)
282 
283  UAS_FCU(m_uas)->send_message_ignore_drop(trajectory);
284  }
285 
286  void handle_trajectory(const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory)
287  {
288  auto tr_desired = boost::make_shared<mavros_msgs::Trajectory>();
289 
290  auto fill_msg_point = [&](RosPoints & p, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t, const size_t i) {
291  fill_msg_position(p.position, t, i);
292  fill_msg_velocity(p.velocity, t, i);
293  fill_msg_acceleration(p.acceleration_or_force, t, i);
294  p.yaw = wrap_pi((M_PI / 2.0f) - t.pos_yaw[i]);
295  p.yaw_rate = t.vel_yaw[i];
296  tr_desired->command[i] = t.command[i];
297  };
298 
299  tr_desired->header = m_uas->synchronized_header("local_origin", trajectory.time_usec);
300 
301  for (int i = 0; i < trajectory.valid_points; ++i)
302  {
303  tr_desired->point_valid[i] = true;
304  }
305 
306  for (int i = trajectory.valid_points; i < NUM_POINTS; ++i)
307  {
308  tr_desired->point_valid[i] = false;
309  }
310 
311  // [[[cog:
312  // for i in range(5):
313  // cog.outl(
314  // "fill_msg_point(tr_desired->point_{i1}, trajectory, {i0});"
315  // .format(i0=i, i1=i + 1, )
316  // )
317  // ]]]
318  fill_msg_point(tr_desired->point_1, trajectory, 0);
319  fill_msg_point(tr_desired->point_2, trajectory, 1);
320  fill_msg_point(tr_desired->point_3, trajectory, 2);
321  fill_msg_point(tr_desired->point_4, trajectory, 3);
322  fill_msg_point(tr_desired->point_5, trajectory, 4);
323  // [[[end]]] (checksum: b6aa0c7395a7a426c25d726b75b6efea)
324 
325  trajectory_desired_pub.publish(tr_desired);
326  }
327 
328  float wrap_pi(float a)
329  {
330  if (!std::isfinite(a)) {
331  return a;
332  }
333 
334  return fmod(a + M_PI, 2.0f * M_PI) - M_PI;
335  }
336 };
337 } // namespace extra_plugins
338 } // namespace mavros
339 
std::shared_ptr< MAVConnInterface const > ConstPtr
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
void publish(const boost::shared_ptr< M > &message) const
void fill_points_velocity(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &velocity, const size_t i)
Definition: trajectory.cpp:98
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::array< float, NUM_POINTS > MavPoints
Type matching mavlink::common::msg::TRAJECTORY::TRAJECTORY_REPRESENTATION_WAYPOINTS fields...
Definition: trajectory.cpp:30
void fill_points_acceleration(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &acceleration, const size_t i)
Definition: trajectory.cpp:107
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void fill_points_yaw_speed(MavPoints &yv, const double yaw_speed, const size_t i)
Definition: trajectory.cpp:123
T transform_orientation_enu_ned(const T &in)
void handle_trajectory(const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory)
Definition: trajectory.cpp:286
static constexpr size_t NUM_POINTS
Points count in TRAJECTORY message.
Definition: trajectory.cpp:27
void fill_points_yaw_wp(MavPoints &y, const double yaw, const size_t i)
Definition: trajectory.cpp:119
void fill_points_all_unused(mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
Definition: trajectory.cpp:146
void fill_points_position(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Point &position, const size_t i)
Definition: trajectory.cpp:89
void fill_msg_position(geometry_msgs::Point &position, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
Definition: trajectory.cpp:164
#define UAS_FCU(uasobjptr)
T transform_frame_ned_enu(const T &in)
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
auto fill_points_unused_path(mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
Definition: trajectory.cpp:136
mavros_msgs::PositionTarget RosPoints
Definition: trajectory.cpp:32
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
T transform_frame_enu_ned(const T &in)
void fill_points_yaw_q(MavPoints &y, const geometry_msgs::Quaternion &orientation, const size_t i)
Definition: trajectory.cpp:127
void path_cb(const nav_msgs::Path::ConstPtr &req)
Send corrected path to the FCU.
Definition: trajectory.cpp:250
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
double quaternion_get_yaw(const Eigen::Quaterniond &q)
void trajectory_cb(const mavros_msgs::Trajectory::ConstPtr &req)
Send corrected path to the FCU.
Definition: trajectory.cpp:200
Trajectory plugin to receive planned path from the FCU and send back to the FCU a corrected path (col...
Definition: trajectory.cpp:40
void fill_msg_acceleration(geometry_msgs::Vector3 &acceleration, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
Definition: trajectory.cpp:182
T transform_orientation_baselink_aircraft(const T &in)
void fill_msg_velocity(geometry_msgs::Vector3 &velocity, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
Definition: trajectory.cpp:173
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
constexpr std::underlying_type< _T >::type enum_value(_T e)


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18