Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
mavros::extra_plugins::VisionPoseEstimatePlugin Class Reference

Vision pose estimate plugin. More...

Inheritance diagram for mavros::extra_plugins::VisionPoseEstimatePlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions ()
 
void initialize (UAS &uas_)
 
 VisionPoseEstimatePlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void send_vision_estimate (const ros::Time &stamp, const Eigen::Affine3d &tr, const geometry_msgs::PoseWithCovariance::_covariance_type &cov)
 Send vision estimate transform to FCU position controller. More...
 
void transform_cb (const geometry_msgs::TransformStamped &transform)
 
void vision_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
 
void vision_cov_cb (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req)
 
- Private Member Functions inherited from mavros::plugin::TF2ListenerMixin< VisionPoseEstimatePlugin >
void tf2_start (const char *_thd_name, void(VisionPoseEstimatePlugin::*cbp)(const geometry_msgs::TransformStamped &))
 
void tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(VisionPoseEstimatePlugin::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
 

Private Attributes

ros::Time last_transform_stamp
 
ros::NodeHandle sp_nh
 
std::string tf_child_frame_id
 
std::string tf_frame_id
 
double tf_rate
 
ros::Subscriber vision_cov_sub
 
ros::Subscriber vision_sub
 
- Private Attributes inherited from mavros::plugin::TF2ListenerMixin< VisionPoseEstimatePlugin >
std::string tf_thd_name
 
std::thread tf_thread
 

Friends

class TF2ListenerMixin
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
typedef boost::shared_ptr< PluginBase const > ConstPtr
 
typedef mavconn::MAVConnInterface::ReceivedCb HandlerCb
 
typedef std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCbHandlerInfo
 
typedef boost::shared_ptr< PluginBasePtr
 
typedef std::vector< HandlerInfoSubscriptions
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void connection_cb (bool connected)
 
void enable_connection_cb ()
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Vision pose estimate plugin.

Send pose estimation from various vision estimators to FCU position and attitude estimators.

Definition at line 34 of file vision_pose_estimate.cpp.


The documentation for this class was generated from the following file:


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18