Vision speed estimate plugin. More...

Public Member Functions | |
| Subscriptions | get_subscriptions () override |
| void | initialize (UAS &uas_) override |
| VisionSpeedEstimatePlugin () | |
Public Member Functions inherited from mavros::plugin::PluginBase | |
| virtual | ~PluginBase () |
Private Member Functions | |
| void | convert_vision_speed (const ros::Time &stamp, const Eigen::Vector3d &vel_enu, const ftf::Covariance3d &cov_enu) |
| Convert vector and covariance from local ENU to local NED frame. More... | |
| void | send_vision_speed_estimate (const uint64_t usec, const Eigen::Vector3d &v, const ftf::Covariance3d &cov) |
| Send vision speed estimate on local NED frame to the FCU. More... | |
| void | twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
| Callback to geometry_msgs/TwistStamped msgs. More... | |
| void | twist_cov_cb (const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &req) |
| Callback to geometry_msgs/TwistWithCovarianceStamped msgs. More... | |
| void | vector_cb (const geometry_msgs::Vector3Stamped::ConstPtr &req) |
| Callback to geometry_msgs/Vector3Stamped msgs. More... | |
Private Attributes | |
| bool | listen_twist |
| If True, listen to Twist data topics. More... | |
| ros::NodeHandle | sp_nh |
| bool | twist_cov |
| If True, listen to TwistWithCovariance data topic. More... | |
| ros::Subscriber | vision_twist_cov_sub |
| Subscriber to geometry_msgs/TwistWithCovarianceStamped msgs. More... | |
| ros::Subscriber | vision_twist_sub |
| Subscriber to geometry_msgs/TwistStamped msgs. More... | |
| ros::Subscriber | vision_vector_sub |
| Subscriber to geometry_msgs/Vector3Stamped msgs. More... | |
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, HandlerCb > | HandlerInfo |
| typedef boost::shared_ptr< PluginBase > | Ptr |
| typedef std::vector< HandlerInfo > | Subscriptions |
Protected Member Functions inherited from mavros::plugin::PluginBase | |
| virtual void | capabilities_cb (UAS::MAV_CAP capabilities) |
| virtual void | connection_cb (bool connected) |
| void | enable_capabilities_cb () |
| void | enable_connection_cb () |
| HandlerInfo | make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing)) |
| HandlerInfo | make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &)) |
| PluginBase () | |
Protected Attributes inherited from mavros::plugin::PluginBase | |
| UAS * | m_uas |
Vision speed estimate plugin.
Send velocity estimation from various vision estimators to FCU position and attitude estimators.
Definition at line 33 of file vision_speed_estimate.cpp.