21 #include <mavros_msgs/AttitudeTarget.h> 22 #include <mavros_msgs/PositionTarget.h> 23 #include <mavros_msgs/GlobalPositionTarget.h> 26 namespace std_plugins {
39 sp_nh(
"~setpoint_raw")
44 PluginBase::initialize(uas_);
85 Eigen::Vector3d ang_vel_ned(0.0, 0.0, tgt.yaw_rate);
89 auto target = boost::make_shared<mavros_msgs::PositionTarget>();
92 target->coordinate_frame = tgt.coordinate_frame;
93 target->type_mask = tgt.type_mask;
98 target->yaw_rate = yaw_rate;
100 target_local_pub.
publish(target);
112 Eigen::Vector3d ang_vel_ned(0.0, 0.0, tgt.yaw_rate);
116 auto target = boost::make_shared<mavros_msgs::GlobalPositionTarget>();
119 target->coordinate_frame = tgt.coordinate_frame;
120 target->type_mask = tgt.type_mask;
121 target->latitude = tgt.lat_int / 1e7;
122 target->longitude = tgt.lon_int / 1e7;
123 target->altitude = tgt.alt;
127 target->yaw_rate = yaw_rate;
129 target_global_pub.
publish(target);
138 Eigen::Quaterniond(tgt.q[0], tgt.q[1], tgt.q[2], tgt.q[3])));
142 auto target = boost::make_shared<mavros_msgs::AttitudeTarget>();
145 target->type_mask = tgt.type_mask;
148 target->thrust = tgt.thrust;
150 target_attitude_pub.
publish(target);
157 Eigen::Vector3d position, velocity, af;
172 Eigen::Vector3d ang_vel_enu(0.0, 0.0, req->yaw_rate);
174 yaw_rate = ang_vel_ned.z();
177 req->header.stamp.toNSec() / 1000000,
178 req->coordinate_frame,
188 Eigen::Vector3d velocity, af;
201 Eigen::Vector3d ang_vel_enu(0.0, 0.0, req->yaw_rate);
203 yaw_rate = ang_vel_ned.z();
206 req->header.stamp.toNSec() / 1000000,
207 req->coordinate_frame,
210 req->longitude * 1e7,
219 double thrust_scaling;
220 Eigen::Quaterniond desired_orientation;
221 Eigen::Vector3d baselink_angular_rate;
222 Eigen::Vector3d body_rate;
227 auto ignore_thrust = req->thrust != 0.0 && !sp_nh.
getParam(
"thrust_scaling", thrust_scaling);
232 "the most likely cause of this is a failure to specify the thrust_scaling parameters " 233 "on px4/apm_config.yaml. Actuation will be ignored.");
236 if (thrust_scaling == 0.0) {
239 thrust = std::min(1.0, std::max(0.0, req->thrust * thrust_scaling));
254 req->header.stamp.toNSec() / 1000000,
256 ned_desired_orientation,
MAVROS Plugin base class.
std::shared_ptr< MAVConnInterface const > ConstPtr
ros::Publisher target_global_pub
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher target_local_pub
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())
friend class SetPositionTargetGlobalIntMixin
friend class SetAttitudeTargetMixin
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void attitude_cb(const mavros_msgs::AttitudeTarget::ConstPtr &req)
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...
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()
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
ros::Publisher target_attitude_pub
void initialize(UAS &uas_)
Plugin initializer.
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)
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
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.
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
T transform_frame_baselink_aircraft(const T &in)
Transform data expressed in Baselink frame to Aircraft frame.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
friend class SetPositionTargetLocalNEDMixin
#define ROS_FATAL_THROTTLE_NAMED(period, name,...)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
ros::Subscriber global_sub
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
ros::Subscriber local_sub
This mixin adds set_position_target_local_ned()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
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()
bool getParam(const std::string &key, std::string &s) const
ros::Subscriber attitude_sub
T transform_orientation_ned_enu(const T &in)
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame...
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...
T transform_orientation_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame...
This mixin adds set_position_target_global_int()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)