Odometry plugin. More...
Public Member Functions | |
Subscriptions | get_subscriptions () override |
void | initialize (UAS &uas_) override |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OdometryPlugin () |
![]() | |
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 | lookup_static_transform (const std::string &target, const std::string &source, Eigen::Affine3d &tf_source2target) |
Lookup static transform with error handling. More... | |
void | odom_cb (const nav_msgs::Odometry::ConstPtr &odom) |
Sends odometry data msgs to the FCU. More... | |
Private Attributes | |
std::string | fcu_odom_child_id_des |
desired orientation of the fcu odometry message's child frame More... | |
std::string | fcu_odom_parent_id_des |
desired orientation of the fcu odometry message's parent 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 | |
![]() | |
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 |
![]() | |
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 () | |
![]() | |
UAS * | m_uas |
Odometry plugin.
Sends odometry data to the FCU estimator and publishes odometry data that comes from FCU.
This plugin is following ROS REP 147. Pose is expressed in parent frame. (Quaternion rotates from child to parent) The twist is expressed in the child frame.