Go to the documentation of this file.
23 #include <geometry_msgs/PoseStamped.h>
24 #include <geometry_msgs/Vector3Stamped.h>
25 #include <mavros_msgs/LandingTarget.h>
28 namespace extra_plugins {
29 using mavlink::common::MAV_FRAME;
30 using mavlink::common::LANDING_TARGET_TYPE;
42 nh(
"~landing_target"),
150 Eigen::Vector2f angle,
152 Eigen::Vector2f
size,
154 Eigen::Quaterniond q,
156 uint8_t position_valid)
158 mavlink::common::msg::LANDING_TARGET lt {};
160 lt.time_usec = time_usec;
161 lt.target_num = target_num;
163 lt.distance = distance;
165 lt.position_valid = position_valid;
166 lt.angle_x =
angle.x();
167 lt.angle_y =
angle.y();
168 lt.size_x =
size.x();
169 lt.size_y =
size.y();
198 float angle_rad = atan(
pos.y() /
pos.x()) * (M_PI / 180.0);
200 if (
pos.x() > 0 &&
pos.y() > 0) {
201 angle.x() = angle_rad;
202 angle.y() = -angle_rad;
204 else if (
pos.x() < 0 &&
pos.y() > 0) {
205 angle.x() = M_PI - angle_rad;
206 angle.y() = angle_rad;
208 else if (
pos.x() < 0 &&
pos.y() < 0) {
209 angle.x() = M_PI + angle_rad;
210 angle.y() = M_PI - angle_rad;
212 else if (
pos.x() > 0 &&
pos.y() < 0) {
213 angle.x() = -angle_rad;
214 angle.y() = M_PI + angle_rad;
233 Eigen::Vector2f
angle;
234 Eigen::Vector2f size_rad;
238 float distance =
pos.norm();
261 size_rad = {2 * (M_PI / 180.0) * atan(
target_size_x / (2 * distance)),
274 uint8_t
id =
static_cast<uint8_t
>(
frame_id.back());
277 "ID: %d frame: %s angular offset: X:%1.3frad, Y:%1.3frad) "
278 "distance: %1.3fm position: X:%1.3fm, Y:%1.3fm, Z:%1.3fm) "
279 "orientation: roll:%1.4frad pitch:%1.4frad yaw:%1.4frad "
280 "size: X:%1.3frad by Y:%1.3frad type: %s",
283 rpy.x(), rpy.y(), rpy.z(), size_rad.x(), size_rad.y(),
301 void handle_landing_target(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::LANDING_TARGET &land_target) {
311 "ID: %d frame: %s angular offset: X:%1.3frad, Y:%1.3frad) "
312 "distance: %1.3fm position: X:%1.3fm, Y:%1.3fm, Z:%1.3fm) "
313 "orientation: roll:%1.4frad pitch:%1.4frad yaw:%1.4frad "
314 "size: X:%1.3frad by Y:%1.3frad type: %s",
315 land_target.target_num,
utils::to_string(
static_cast<MAV_FRAME
>(land_target.frame)).c_str(),
316 land_target.angle_x, land_target.angle_y, land_target.distance,
317 position.x(), position.y(), position.z(), rpy.x(), rpy.y(), rpy.z(), land_target.size_x, land_target.size_y,
318 utils::to_string(
static_cast<LANDING_TARGET_TYPE
>(land_target.type)).c_str());
320 auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
329 geometry_msgs::TransformStamped
transform;
331 transform.header.stamp = pose->header.stamp;
332 transform.header.frame_id =
"landing_target_" + boost::lexical_cast<std::string>(land_target.target_num);
335 transform.transform.rotation = pose->pose.orientation;
341 auto tg_size_msg = boost::make_shared<geometry_msgs::Vector3Stamped>();
386 Eigen::Vector2f(req->angle[0], req->angle[1]),
388 Eigen::Vector2f(req->size[0], req->size[1]),
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
T transform_frame_enu_ned(const T &in)
tf2_ros::TransformBroadcaster tf2_broadcaster
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
std::vector< HandlerInfo > Subscriptions
ros::Time last_transform_stamp
#define ROS_DEBUG_THROTTLE_NAMED(period, name,...)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void handle_landing_target(const mavlink::mavlink_message_t *msg, mavlink::common::msg::LANDING_TARGET &land_target)
Receive landing target from FCU.
#define UAS_FCU(uasobjptr)
void transform_cb(const geometry_msgs::TransformStamped &transform)
callback for TF2 listener
std::shared_ptr< MAVConnInterface const > ConstPtr
void tf2_start(const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(D::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
Subscriptions get_subscriptions() override
ros::Subscriber land_target_sub
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Publisher land_target_pub
Eigen::Quaterniond mavlink_to_quaternion(const std::array< float, 4 > &q)
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
T transform_orientation_ned_enu(const T &in)
std::string to_string(ADSB_ALTITUDE_TYPE e)
T transform_orientation_aircraft_baselink(const T &in)
T transform_orientation_baselink_aircraft(const T &in)
void send_landing_target(const ros::Time &stamp, const Eigen::Affine3d &tr)
Send landing target transform to FCU.
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void landing_target(uint64_t time_usec, uint8_t target_num, uint8_t frame, Eigen::Vector2f angle, float distance, Eigen::Vector2f size, Eigen::Vector3d pos, Eigen::Quaterniond q, uint8_t type, uint8_t position_valid)
void landtarget_cb(const mavros_msgs::LandingTarget::ConstPtr &req)
callback for raw LandingTarget msgs topic - useful if one has the data processed in another node
void pose_cb(const geometry_msgs::PoseStamped::ConstPtr &req)
callback for PoseStamped msgs topic
std::string tf_child_frame_id
T transform_orientation_enu_ned(const T &in)
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
ros::Publisher lt_marker_pub
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
void cartesian_to_displacement(const Eigen::Vector3d &pos, Eigen::Vector2f &angle)
Displacement: (not to be mixed with angular displacement)
virtual void initialize(UAS &uas)
T param(const std::string ¶m_name, const T &default_val) const
#define ROS_INFO_STREAM_NAMED(name, args)
Eigen::Vector3d quaternion_to_rpy(const Eigen::Quaterniond &q)
friend class TF2ListenerMixin
T transform_frame_ned_enu(const T &in)
std::string land_target_type
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void initialize(UAS &uas_) override
constexpr std::underlying_type< _T >::type enum_value(_T e)
mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
void quaternion_to_mavlink(const Eigen::Quaternion< _Scalar > &q, std::array< float, 4 > &qmsg)
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08