|
void | cartesian_to_displacement (const Eigen::Vector3d &pos, Eigen::Vector2f &angle) |
| Displacement: (not to be mixed with angular displacement) More...
|
|
void | handle_landing_target (const mavlink::mavlink_message_t *msg, mavlink::common::msg::LANDING_TARGET &land_target) |
| Receive landing target from FCU. More...
|
|
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 More...
|
|
void | pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req) |
| callback for PoseStamped msgs topic More...
|
|
void | send_landing_target (const ros::Time &stamp, const Eigen::Affine3d &tr) |
| Send landing target transform to FCU. More...
|
|
void | transform_cb (const geometry_msgs::TransformStamped &transform) |
| callback for TF2 listener More...
|
|
void | tf2_start (const char *_thd_name, void(LandingTargetPlugin::*cbp)(const geometry_msgs::TransformStamped &)) |
|
void | tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(LandingTargetPlugin::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &)) |
|
Landing Target plugin.
This plugin is intended to publish the location of a landing area captured from a downward facing camera to the FCU and/or receive landing target tracking data coming from the FCU.
Definition at line 38 of file landing_target.cpp.