Odometry plugin. More...

Public Member Functions | |
| Subscriptions | get_subscriptions () |
| void | initialize (UAS &uas_) |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OdometryPlugin () |
Public Member Functions inherited from mavros::plugin::PluginBase | |
| virtual | ~PluginBase () |
Private Member Functions | |
| void | handle_odom (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ODOMETRY &odom_msg) |
| Handle ODOMETRY MAVlink message. More... | |
| void | odom_cb (const nav_msgs::Odometry::ConstPtr &odom) |
| Sends odometry data msgs to the FCU. More... | |
| void | transform_lookup (const std::string &frame_id, const std::string &child_frame_id, const std::string &local_frame_orientation, const std::string &body_frame_orientation, Eigen::Affine3d &tf_parent2local, Eigen::Affine3d &tf_child2local, Eigen::Affine3d &tf_parent2body, Eigen::Affine3d &tf_child2body) |
| Lookup transforms. More... | |
Private Attributes | |
| MAV_FRAME | bf_id |
| body frame (pose) ID More... | |
| std::string | body_frame_orientation_in_desired |
| orientation of the body frame (input data) More... | |
| std::string | body_frame_orientation_out_desired |
| orientation of the body frame (output data) More... | |
| std::string | child_frame_id |
| child frame identifier More... | |
| std::string | frame_id |
| parent frame identifier More... | |
| MAV_FRAME | lf_id |
| local frame (pose) ID More... | |
| std::string | local_frame_in |
| orientation and source of the input local frame More... | |
| std::string | local_frame_orientation_in |
| orientation of the local frame (input data) More... | |
| std::string | local_frame_orientation_out |
| orientation of the local frame (output data) More... | |
| std::string | local_frame_out |
| orientation and source of the output local frame More... | |
| ros::NodeHandle | odom_nh |
| node handler More... | |
| ros::Publisher | odom_pub |
| nav_msgs/Odometry publisher More... | |
| ros::Subscriber | odom_sub |
| nav_msgs/Odometry subscriber 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 | 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 | |
| UAS * | m_uas |