23 #include <geometry_msgs/TransformStamped.h>
43 float yaw,
float yaw_rate)
45 mavros::UAS *m_uas_ =
static_cast<D *
>(
this)->m_uas;
46 mavlink::common::msg::SET_POSITION_TARGET_LOCAL_NED sp = {};
57 sp.time_boot_ms = time_boot_ms;
58 sp.coordinate_frame = coordinate_frame;
59 sp.type_mask = type_mask;
61 sp.yaw_rate = yaw_rate;
73 UAS_FCU(m_uas_)->send_message_ignore_drop(sp);
86 int32_t lat_int, int32_t lon_int,
float alt,
89 float yaw,
float yaw_rate)
91 mavros::UAS *m_uas_ =
static_cast<D *
>(
this)->m_uas;
92 mavlink::common::msg::SET_POSITION_TARGET_GLOBAL_INT sp = {};
103 sp.time_boot_ms = time_boot_ms;
104 sp.coordinate_frame = coordinate_frame;
105 sp.type_mask = type_mask;
106 sp.lat_int = lat_int;
107 sp.lon_int = lon_int;
110 sp.yaw_rate = yaw_rate;
119 UAS_FCU(m_uas_)->send_message_ignore_drop(sp);
132 Eigen::Quaterniond orientation,
133 Eigen::Vector3d body_rate,
136 mavros::UAS *m_uas_ =
static_cast<D *
>(
this)->m_uas;
137 mavlink::common::msg::SET_ATTITUDE_TARGET sp = {};
148 sp.time_boot_ms = time_boot_ms;
149 sp.type_mask = type_mask;
151 sp.body_roll_rate = body_rate.x();
152 sp.body_pitch_rate = body_rate.y();
153 sp.body_yaw_rate = body_rate.z();
156 UAS_FCU(m_uas_)->send_message_ignore_drop(sp);
178 void tf2_start(
const char *_thd_name,
void (D::*cbp)(
const geometry_msgs::TransformStamped &) )
181 auto tf_transform_cb = std::bind(cbp,
static_cast<D *
>(
this), std::placeholders::_1);
183 tf_thread = std::thread([
this, tf_transform_cb]() {
186 mavros::UAS *m_uas_ =
static_cast<D *
>(
this)->m_uas;
187 std::string &_frame_id =
static_cast<D *
>(
this)->tf_frame_id;
188 std::string &_child_frame_id =
static_cast<D *
>(
this)->tf_child_frame_id;
190 ros::Rate rate(
static_cast<D *
>(
this)->tf_rate);
197 tf_transform_cb(transform);
219 tf_thread = std::thread([
this, cbp, &topic_sub]() {
222 mavros::UAS *m_uas_ =
static_cast<D *
>(
this)->m_uas;
224 std::string &_frame_id =
static_cast<D *
>(
this)->tf_frame_id;
225 std::string &_child_frame_id =
static_cast<D *
>(
this)->tf_child_frame_id;
229 ros::Rate rate(
static_cast<D *
>(
this)->tf_rate);
237 tf2_filter.registerCallback(boost::bind(cbp,
static_cast<D *
>(
this), transform, _1));