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));
164 void fill_msg_position(geometry_msgs::Point &position,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
168 position.x = position_enu.x();
169 position.y = position_enu.y();
170 position.z = position_enu.z();
173 void fill_msg_velocity(geometry_msgs::Vector3 &velocity,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
177 velocity.x = velocity_enu.x();
178 velocity.y = velocity_enu.y();
179 velocity.z = velocity_enu.z();
182 void fill_msg_acceleration(geometry_msgs::Vector3 &acceleration,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t,
const size_t i)
186 acceleration.x = acceleration_enu.x();
187 acceleration.y = acceleration_enu.y();
188 acceleration.z = acceleration_enu.z();
202 ROS_ASSERT(NUM_POINTS == req->point_valid.size());
204 mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
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];
209 auto valid_so_far = trajectory.valid_points;
215 trajectory.valid_points = valid_so_far + 1;
221 t.command[i] = UINT16_MAX;
224 trajectory.time_usec = req->header.stamp.toNSec() / 1000;
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);
252 mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS trajectory {};
254 trajectory.time_usec = req->header.stamp.toNSec() / 1000;
255 trajectory.valid_points = std::min(NUM_POINTS, req->poses.size());
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) {
263 auto &pose = req->poses[i].pose;
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);
286 void handle_trajectory(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory)
288 auto tr_desired = boost::make_shared<mavros_msgs::Trajectory>();
290 auto fill_msg_point = [&](
RosPoints & p,
const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &
t,
const size_t i) {
294 p.yaw =
wrap_pi((M_PI / 2.0
f) - t.pos_yaw[i]);
295 p.yaw_rate = t.vel_yaw[i];
296 tr_desired->command[i] = t.command[i];
301 for (
int i = 0; i < trajectory.valid_points; ++i)
303 tr_desired->point_valid[i] =
true;
306 for (
int i = trajectory.valid_points; i < NUM_POINTS; ++i)
308 tr_desired->point_valid[i] =
false;
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);
325 trajectory_desired_pub.
publish(tr_desired);
330 if (!std::isfinite(a)) {
334 return fmod(a + M_PI, 2.0
f * M_PI) - M_PI;
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)
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...
void fill_points_acceleration(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &acceleration, const size_t i)
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)
T transform_orientation_enu_ned(const T &in)
void handle_trajectory(const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory)
static constexpr size_t NUM_POINTS
Points count in TRAJECTORY message.
ros::Subscriber trajectory_generated_sub
void fill_points_yaw_wp(MavPoints &y, const double yaw, const size_t i)
ros::NodeHandle trajectory_nh
void fill_points_all_unused(mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
void initialize(UAS &uas_)
void fill_points_position(MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Point &position, const size_t i)
void fill_msg_position(geometry_msgs::Point &position, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
#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)
mavros_msgs::PositionTarget RosPoints
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Subscriptions get_subscriptions()
T transform_frame_enu_ned(const T &in)
void fill_points_yaw_q(MavPoints &y, const geometry_msgs::Quaternion &orientation, const size_t i)
void path_cb(const nav_msgs::Path::ConstPtr &req)
Send corrected path to the FCU.
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.
void fill_msg_acceleration(geometry_msgs::Vector3 &acceleration, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i)
ros::Publisher trajectory_desired_pub
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)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
constexpr std::underlying_type< _T >::type enum_value(_T e)