setpoint_raw.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2015,2016 Vladimir Ermakov.
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 <mavros_msgs/AttitudeTarget.h>
22 #include <mavros_msgs/PositionTarget.h>
23 #include <mavros_msgs/GlobalPositionTarget.h>
24 
25 namespace mavros {
26 namespace std_plugins {
34  private plugin::SetPositionTargetLocalNEDMixin<SetpointRawPlugin>,
35  private plugin::SetPositionTargetGlobalIntMixin<SetpointRawPlugin>,
36  private plugin::SetAttitudeTargetMixin<SetpointRawPlugin> {
37 public:
39  sp_nh("~setpoint_raw")
40  { }
41 
42  void initialize(UAS &uas_) override
43  {
44  PluginBase::initialize(uas_);
45 
46  bool tf_listen;
47 
51  target_local_pub = sp_nh.advertise<mavros_msgs::PositionTarget>("target_local", 10);
52  target_global_pub = sp_nh.advertise<mavros_msgs::GlobalPositionTarget>("target_global", 10);
53  target_attitude_pub = sp_nh.advertise<mavros_msgs::AttitudeTarget>("target_attitude", 10);
54 
55  // Set Thrust scaling in px4_config.yaml, setpoint_raw block.
56  if (!sp_nh.getParam("thrust_scaling", thrust_scaling))
57  {
58  ROS_WARN_THROTTLE_NAMED(5, "setpoint_raw", "thrust_scaling parameter is unset. Attitude (and angular rate/thrust) setpoints will be ignored.");
59  thrust_scaling = -1.0;
60  }
61  }
62 
64  {
65  return {
69  };
70  }
71 
72 private:
75  friend class SetAttitudeTargetMixin;
77 
80 
82 
83  /* -*- message handlers -*- */
84  void handle_position_target_local_ned(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_LOCAL_NED &tgt)
85  {
86  // Transform desired position,velocities,and accels from ENU to NED frame
87  auto position = ftf::transform_frame_ned_enu(Eigen::Vector3d(tgt.x, tgt.y, tgt.z));
88  auto velocity = ftf::transform_frame_ned_enu(Eigen::Vector3d(tgt.vx, tgt.vy, tgt.vz));
89  auto af = ftf::transform_frame_ned_enu(Eigen::Vector3d(tgt.afx, tgt.afy, tgt.afz));
90  float yaw = ftf::quaternion_get_yaw(
93  ftf::quaternion_from_rpy(0.0, 0.0, tgt.yaw))));
94  Eigen::Vector3d ang_vel_ned(0.0, 0.0, tgt.yaw_rate);
95  auto ang_vel_enu = ftf::transform_frame_ned_enu(ang_vel_ned);
96  float yaw_rate = ang_vel_enu.z();
97 
98  auto target = boost::make_shared<mavros_msgs::PositionTarget>();
99 
100  target->header.stamp = m_uas->synchronise_stamp(tgt.time_boot_ms);
101  target->coordinate_frame = tgt.coordinate_frame;
102  target->type_mask = tgt.type_mask;
103  tf::pointEigenToMsg(position, target->position);
104  tf::vectorEigenToMsg(velocity, target->velocity);
105  tf::vectorEigenToMsg(af, target->acceleration_or_force);
106  target->yaw = yaw;
107  target->yaw_rate = yaw_rate;
108 
109  target_local_pub.publish(target);
110  }
111 
112  void handle_position_target_global_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &tgt)
113  {
114  // Transform desired velocities from ENU to NED frame
115  auto velocity = ftf::transform_frame_ned_enu(Eigen::Vector3d(tgt.vx, tgt.vy, tgt.vz));
116  auto af = ftf::transform_frame_ned_enu(Eigen::Vector3d(tgt.afx, tgt.afy, tgt.afz));
117  float yaw = ftf::quaternion_get_yaw(
120  ftf::quaternion_from_rpy(0.0, 0.0, tgt.yaw))));
121  Eigen::Vector3d ang_vel_ned(0.0, 0.0, tgt.yaw_rate);
122  auto ang_vel_enu = ftf::transform_frame_ned_enu(ang_vel_ned);
123  float yaw_rate = ang_vel_enu.z();
124 
125  auto target = boost::make_shared<mavros_msgs::GlobalPositionTarget>();
126 
127  target->header.stamp = m_uas->synchronise_stamp(tgt.time_boot_ms);
128  target->coordinate_frame = tgt.coordinate_frame;
129  target->type_mask = tgt.type_mask;
130  target->latitude = tgt.lat_int / 1e7;
131  target->longitude = tgt.lon_int / 1e7;
132  target->altitude = tgt.alt;
133  tf::vectorEigenToMsg(velocity, target->velocity);
134  tf::vectorEigenToMsg(af, target->acceleration_or_force);
135  target->yaw = yaw;
136  target->yaw_rate = yaw_rate;
137 
138  target_global_pub.publish(target);
139  }
140 
141  void handle_attitude_target(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE_TARGET &tgt)
142  {
143  // Transform orientation from baselink -> ENU
144  // to aircraft -> NED
145  auto orientation = ftf::transform_orientation_ned_enu(
148 
149  auto body_rate = ftf::transform_frame_baselink_aircraft(Eigen::Vector3d(tgt.body_roll_rate, tgt.body_pitch_rate, tgt.body_yaw_rate));
150 
151  auto target = boost::make_shared<mavros_msgs::AttitudeTarget>();
152 
153  target->header.stamp = m_uas->synchronise_stamp(tgt.time_boot_ms);
154  target->type_mask = tgt.type_mask;
155  tf::quaternionEigenToMsg(orientation, target->orientation);
156  tf::vectorEigenToMsg(body_rate, target->body_rate);
157  target->thrust = tgt.thrust;
158 
159  target_attitude_pub.publish(target);
160  }
161 
162  /* -*- callbacks -*- */
163 
165  {
166  Eigen::Vector3d position, velocity, af;
167  float yaw, yaw_rate;
168 
169  tf::pointMsgToEigen(req->position, position);
170  tf::vectorMsgToEigen(req->velocity, velocity);
171  tf::vectorMsgToEigen(req->acceleration_or_force, af);
172 
173  // Transform frame ENU->NED
174  if (req->coordinate_frame == mavros_msgs::PositionTarget::FRAME_BODY_NED || req->coordinate_frame == mavros_msgs::PositionTarget::FRAME_BODY_OFFSET_NED) {
175  position = ftf::transform_frame_baselink_aircraft(position);
176  velocity = ftf::transform_frame_baselink_aircraft(velocity);
180  ftf::quaternion_from_rpy(0.0, 0.0, req->yaw)));
181  } else {
182  position = ftf::transform_frame_enu_ned(position);
183  velocity = ftf::transform_frame_enu_ned(velocity);
188  ftf::quaternion_from_rpy(0.0, 0.0, req->yaw))));
189  }
190 
191  Eigen::Vector3d ang_vel_enu(0.0, 0.0, req->yaw_rate);
192  auto ang_vel_ned = ftf::transform_frame_ned_enu(ang_vel_enu);
193  yaw_rate = ang_vel_ned.z();
194 
196  req->header.stamp.toNSec() / 1000000,
197  req->coordinate_frame,
198  req->type_mask,
199  position,
200  velocity,
201  af,
202  yaw, yaw_rate);
203  }
204 
206  {
207  Eigen::Vector3d velocity, af;
208  float yaw, yaw_rate;
209 
210  tf::vectorMsgToEigen(req->velocity, velocity);
211  tf::vectorMsgToEigen(req->acceleration_or_force, af);
212 
213  // Transform frame ENU->NED
214  velocity = ftf::transform_frame_enu_ned(velocity);
219  ftf::quaternion_from_rpy(0.0, 0.0, req->yaw))));
220  Eigen::Vector3d ang_vel_enu(0.0, 0.0, req->yaw_rate);
221  auto ang_vel_ned = ftf::transform_frame_ned_enu(ang_vel_enu);
222  yaw_rate = ang_vel_ned.z();
223 
225  req->header.stamp.toNSec() / 1000000,
226  req->coordinate_frame,
227  req->type_mask,
228  req->latitude * 1e7,
229  req->longitude * 1e7,
230  req->altitude,
231  velocity,
232  af,
233  yaw, yaw_rate);
234  }
235 
237  {
238  Eigen::Quaterniond desired_orientation;
239  Eigen::Vector3d baselink_angular_rate;
240  Eigen::Vector3d body_rate;
241  double thrust;
242 
243  // ignore thrust is false by default, unless no thrust scaling is set or thrust is zero
244  auto ignore_thrust = req->thrust != 0.0 && thrust_scaling < 0.0;
245 
246  if (ignore_thrust) {
247  // I believe it's safer without sending zero thrust, but actually ignoring the actuation.
248  ROS_FATAL_THROTTLE_NAMED(5, "setpoint_raw", "Recieved thrust, but ignore_thrust is true: "
249  "the most likely cause of this is a failure to specify the thrust_scaling parameters "
250  "on px4/apm_config.yaml. Actuation will be ignored.");
251  return;
252  } else {
253  if (thrust_scaling == 0.0) {
254  ROS_WARN_THROTTLE_NAMED(5, "setpoint_raw", "thrust_scaling parameter is set to zero.");
255  }
256  thrust = std::min(1.0, std::max(0.0, req->thrust * thrust_scaling));
257  }
258 
259  // Take care of attitude setpoint
260  desired_orientation = ftf::to_eigen(req->orientation);
261 
262  // Transform desired orientation to represent aircraft->NED,
263  // MAVROS operates on orientation of base_link->ENU
264  auto ned_desired_orientation = ftf::transform_orientation_enu_ned(
265  ftf::transform_orientation_baselink_aircraft(desired_orientation));
266 
268  ftf::to_eigen(req->body_rate));
269 
271  req->header.stamp.toNSec() / 1000000,
272  req->type_mask,
273  ned_desired_orientation,
274  body_rate,
275  thrust);
276 
277  }
278 };
279 } // namespace std_plugins
280 } // namespace mavros
281 
MAVROS Plugin base class.
Definition: mavros_plugin.h:36
std::shared_ptr< MAVConnInterface const > ConstPtr
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
MAVROS Plugin base.
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
Definition: mavros_plugin.h:87
void attitude_cb(const mavros_msgs::AttitudeTarget::ConstPtr &req)
Eigen::Quaterniond mavlink_to_quaternion(const std::array< float, 4 > &q)
Convert Mavlink float[4] quaternion to Eigen.
Definition: frame_tf.h:384
void global_cb(const mavros_msgs::GlobalPositionTarget::ConstPtr &req)
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.
T transform_orientation_enu_ned(const T &in)
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame...
Definition: frame_tf.h:169
void handle_position_target_global_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &tgt)
void local_cb(const mavros_msgs::PositionTarget::ConstPtr &req)
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:74
T transform_orientation_absolute_frame_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame...
Definition: frame_tf.h:197
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
void publish(const boost::shared_ptr< M > &message) const
UAS for plugins.
Definition: mavros_uas.h:67
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
bool getParam(const std::string &key, std::string &s) const
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
void handle_position_target_local_ned(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_LOCAL_NED &tgt)
Mixin for setpoint plugins.
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
Definition: frame_tf.h:215
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
T transform_frame_baselink_aircraft(const T &in)
Transform data expressed in Baselink frame to Aircraft frame.
Definition: frame_tf.h:242
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_FATAL_THROTTLE_NAMED(period, name,...)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
Definition: frame_tf.h:224
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
This mixin adds set_position_target_local_ned()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:47
void set_position_target_global_int(uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT.
double quaternion_get_yaw(const Eigen::Quaterniond &q)
Get Yaw angle from quaternion.
This mixin adds set_attitude_target()
T transform_orientation_ned_enu(const T &in)
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame...
Definition: frame_tf.h:160
void handle_attitude_target(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE_TARGET &tgt)
void set_attitude_target(uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond orientation, Eigen::Vector3d body_rate, float thrust)
Message sepecification: https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET.
T transform_orientation_baselink_aircraft(const T &in)
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame...
Definition: frame_tf.h:187
T transform_orientation_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame...
Definition: frame_tf.h:178
This mixin adds set_position_target_global_int()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void initialize(UAS &uas_) override
Plugin initializer.


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50