Wheel odometry plugin. More...
Public Member Functions | |
Subscriptions | get_subscriptions () override |
void | initialize (UAS &uas_) override |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | WheelOdometryPlugin () |
Public Member Functions inherited from mavros::plugin::PluginBase | |
virtual | ~PluginBase () |
Private Types | |
enum | OM { OM::NONE, OM::RPM, OM::DIST } |
Odometry computation modes. More... | |
Private Member Functions | |
void | handle_rpm (const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RPM &rpm) |
Handle Ardupilot RPM MAVlink message. Message specification: http://mavlink.io/en/messages/ardupilotmega.html#RPM. More... | |
void | handle_wheel_distance (const mavlink::mavlink_message_t *msg, mavlink::common::msg::WHEEL_DISTANCE &wheel_dist) |
Handle WHEEL_DISTANCE MAVlink message. Message specification: https://mavlink.io/en/messages/common.html#WHEEL_DISTANCE. More... | |
void | process_measurement (std::vector< double > measurement, bool rpm, ros::Time time, ros::Time time_pub) |
Process wheel measurement. More... | |
void | publish_odometry (ros::Time time) |
Publish odometry. Odometry is computed from the very start but no pose info is published until we have initial orientation (yaw). Once we get it, the robot's current pose is updated with it and starts to be published. Twist info doesn't depend on initial orientation so is published from the very start. More... | |
void | update_odometry (std::vector< double > distance, double dt) |
Update odometry (currently, only 2-wheels differential configuration implemented). Odometry is computed for robot's origin (IMU). More... | |
void | update_odometry_diffdrive (std::vector< double > distance, double dt) |
Update odometry for differential drive robot. Odometry is computed for robot's origin (IMU). The wheels are assumed to be parallel to the robot's x-direction (forward) and with the same x-offset. No slip is assumed (Instantaneous Center of Curvature (ICC) along the axis connecting the wheels). All computations are performed for ROS frame conventions. The approach is the extended and more accurate version of standard one described in the book https://github.com/correll/Introduction-to-Autonomous-Robots and at the page (with some typos fixed) http://correll.cs.colorado.edu/?p=1307 The extension is that exact pose update is used instead of approximate, and that the robot's origin can be specified anywhere instead of the middle-point between the wheels. More... | |
Private Attributes | |
std::string | child_frame_id |
body-fixed frame for topic headers More... | |
int | count |
requested number of wheels to compute odometry More... | |
int | count_meas |
number of wheels in measurements More... | |
ros::Publisher | dist_pub |
std::string | frame_id |
origin frame for topic headers More... | |
std::vector< double > | measurement_prev |
previous measurement More... | |
OM | odom_mode |
odometry computation mode More... | |
ros::Publisher | odom_pub |
bool | raw_send |
send wheel's RPM and cumulative distance More... | |
ros::Publisher | rpm_pub |
Eigen::Vector3d | rpose |
Robot origin 2D-state (SI units) More... | |
Eigen::Matrix3d | rpose_cov |
pose error 1-var More... | |
Eigen::Vector3d | rtwist |
twist (vx, vy, vyaw) More... | |
Eigen::Vector3d | rtwist_cov |
twist error 1-var (vx_cov, vy_cov, vyaw_cov) More... | |
std::string | tf_child_frame_id |
frame for TF and Pose More... | |
std::string | tf_frame_id |
origin for TF More... | |
bool | tf_send |
send TF More... | |
ros::Time | time_prev |
timestamp of previous measurement More... | |
ros::Publisher | twist_pub |
bool | twist_send |
send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry More... | |
double | vel_cov |
wheel velocity measurement error 1-var (m/s) More... | |
std::vector< Eigen::Vector2d > | wheel_offset |
wheel x,y offsets (m,NED) More... | |
std::vector< double > | wheel_radius |
wheel radiuses (m) More... | |
ros::NodeHandle | wo_nh |
bool | yaw_initialized |
initial yaw initialized (from IMU) 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 |
Wheel odometry plugin.
This plugin allows computing and publishing wheel odometry coming from FCU wheel encoders. Can use either wheel's RPM or WHEEL_DISTANCE messages (the latter gives better accuracy).
Definition at line 35 of file wheel_odometry.cpp.