23 #include <geometry_msgs/TransformStamped.h> 43 float yaw,
float yaw_rate)
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)
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,
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 &) )
180 tf_thd_name = _thd_name;
181 auto tf_transform_cb = std::bind(cbp, static_cast<D *>(
this), std::placeholders::_1);
183 tf_thread = std::thread([
this, tf_transform_cb]() {
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);
195 auto transform = m_uas_->tf2_buffer.lookupTransform(
200 ROS_ERROR_NAMED(
"tf2_buffer",
"%s: %s", tf_thd_name.c_str(), ex.what());
217 tf_thd_name = _thd_name;
219 tf_thread = std::thread([
this, cbp, &topic_sub]() {
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);
234 auto transform = m_uas_->tf2_buffer.lookupTransform(
240 ROS_ERROR_NAMED(
"tf2_buffer",
"%s: %s", tf_thd_name.c_str(), ex.what());
std::shared_ptr< MAVConnInterface const > ConstPtr
This mixin adds TF2 listener thread to plugin.
bool set_this_thread_name(const std::string &name, Args &&...args)
void tf2_start(const char *_thd_name, void(D::*cbp)(const geometry_msgs::TransformStamped &))
start tf listener
void msg_set_target(_T &msg)
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.
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
This mixin adds set_position_target_local_ned()
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.
This mixin adds set_attitude_target()
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.
#define ROS_ERROR_NAMED(name,...)
void quaternion_to_mavlink(const Eigen::Quaterniond &q, std::array< float, 4 > &qmsg)
Store Quaternion to MAVLink float[4] format.
This mixin adds set_position_target_global_int()
void tf2_start(const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(D::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
start tf listener syncronized with another topic
Connection registerCallback(const C &callback)