18 #include <mavros_msgs/Trajectory.h>
19 #include <mavros_msgs/PositionTarget.h>
20 #include <nav_msgs/Path.h>
23 namespace extra_plugins {
93 x[i] = position_ned.x();
94 y[i] = position_ned.y();
95 z[i] = position_ned.z();
102 x[i] = velocity_ned.x();
103 y[i] = velocity_ned.y();
104 z[i] = velocity_ned.z();
111 x[i] = acceleration_ned.x();
112 y[i] = acceleration_ned.y();
113 z[i] = acceleration_ned.z();
120 y[i] =
wrap_pi(-yaw + (M_PI / 2.0
f));
133 y[i] =
wrap_pi(-yaw_wp + (M_PI / 2.0
f));
177 void fill_msg_position(geometry_msgs::Point &position,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
181 position.x = position_enu.x();
182 position.y = position_enu.y();
183 position.z = position_enu.z();
186 void fill_msg_velocity(geometry_msgs::Vector3 &velocity,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
190 velocity.x = velocity_enu.x();
191 velocity.y = velocity_enu.y();
192 velocity.z = velocity_enu.z();
195 void fill_msg_acceleration(geometry_msgs::Vector3 &acceleration,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
199 acceleration.x = acceleration_enu.x();
200 acceleration.y = acceleration_enu.y();
201 acceleration.z = acceleration_enu.z();
217 if (req->type == mavros_msgs::Trajectory::MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS) {
218 mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
220 auto fill_point_rep_waypoints = [&](mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t,
const RosPoints &rp,
const size_t i) {
221 const auto valid = req->point_valid[i];
223 auto valid_so_far = trajectory.valid_points;
229 trajectory.valid_points = valid_so_far + 1;
235 t.command[i] = UINT16_MAX;
245 fill_point_rep_waypoints(trajectory, req->point_1, 0);
246 fill_point_rep_waypoints(trajectory, req->point_2, 1);
247 fill_point_rep_waypoints(trajectory, req->point_3, 2);
248 fill_point_rep_waypoints(trajectory, req->point_4, 3);
249 fill_point_rep_waypoints(trajectory, req->point_5, 4);
252 trajectory.time_usec = req->header.stamp.toNSec() / 1000;
255 mavlink::common::msg::TRAJECTORY_REPRESENTATION_BEZIER trajectory {};
256 auto fill_point_rep_bezier = [&](mavlink::common::msg::TRAJECTORY_REPRESENTATION_BEZIER & t,
const RosPoints &rp,
const size_t i) {
257 const auto valid = req->point_valid[i];
259 auto valid_so_far = trajectory.valid_points;
265 trajectory.valid_points = valid_so_far + 1;
277 fill_point_rep_bezier(trajectory, req->point_1, 0);
278 fill_point_rep_bezier(trajectory, req->point_2, 1);
279 fill_point_rep_bezier(trajectory, req->point_3, 2);
280 fill_point_rep_bezier(trajectory, req->point_4, 3);
281 fill_point_rep_bezier(trajectory, req->point_5, 4);
284 trajectory.time_usec = req->header.stamp.toNSec() / 1000;
298 mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
300 trajectory.time_usec = req->header.stamp.toNSec() / 1000;
301 trajectory.valid_points = std::min(
NUM_POINTS, req->poses.size());
303 auto fill_point = [&](mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t,
const size_t i) {
304 t.command[i] = UINT16_MAX;
305 if (req->poses.size() < i + 1) {
309 auto &pose = req->poses[i].pose;
322 fill_point(trajectory, 0);
323 fill_point(trajectory, 1);
324 fill_point(trajectory, 2);
325 fill_point(trajectory, 3);
326 fill_point(trajectory, 4);
332 void handle_trajectory(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory)
334 auto tr_desired = boost::make_shared<mavros_msgs::Trajectory>();
336 auto fill_msg_point = [&](
RosPoints & p,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS & t,
const size_t i) {
340 p.yaw =
wrap_pi((M_PI / 2.0
f) - t.pos_yaw[i]);
341 p.yaw_rate = t.vel_yaw[i];
342 tr_desired->command[i] = t.command[i];
347 if (trajectory.valid_points > tr_desired->point_valid.size()) {
351 for (
int i = 0; i < trajectory.valid_points; ++i)
353 tr_desired->point_valid[i] =
true;
356 for (
int i = trajectory.valid_points; i <
NUM_POINTS; ++i)
358 tr_desired->point_valid[i] =
false;
368 fill_msg_point(tr_desired->point_1, trajectory, 0);
369 fill_msg_point(tr_desired->point_2, trajectory, 1);
370 fill_msg_point(tr_desired->point_3, trajectory, 2);
371 fill_msg_point(tr_desired->point_4, trajectory, 3);
372 fill_msg_point(tr_desired->point_5, trajectory, 4);
380 if (!std::isfinite(a)) {
384 return fmod(a + M_PI, 2.0
f * M_PI) - M_PI;