18 #include <mavros_msgs/WheelOdomStamped.h> 20 #include <geometry_msgs/TwistWithCovarianceStamped.h> 21 #include <nav_msgs/Odometry.h> 27 namespace extra_plugins {
37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 wo_nh(
"~wheel_odometry"),
119 if (separation < 1.
e-5) {
121 ROS_WARN_NAMED(
"wo",
"WO: Separation between the first two wheels is too small (%f).", separation);
153 ROS_WARN_NAMED(
"wo",
"WO: No odometry computations will be performed.");
220 Eigen::Rotation2Dd rot(yaw);
221 rpose.head(2) = rot * rpose.head(2);
224 ROS_INFO_NAMED(
"wo",
"WO: Initial yaw (deg): %f", yaw / M_PI * 180.0);
225 yaw_initialized =
true;
229 geometry_msgs::Quaternion quat;
234 geometry_msgs::TwistWithCovariance twist_cov;
236 twist_cov.twist.linear.x =
rtwist(0);
237 twist_cov.twist.linear.y =
rtwist(1);
238 twist_cov.twist.linear.z = 0.0;
240 twist_cov.twist.angular.x = 0.0;
241 twist_cov.twist.angular.y = 0.0;
242 twist_cov.twist.angular.z =
rtwist(2);
245 twist_cov_map.setZero();
247 twist_cov_map.block<1, 1>(5, 5).diagonal() <<
rtwist_cov(2);
251 auto twist_cov_t = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
253 twist_cov_t->header.stamp = time;
254 twist_cov_t->header.frame_id =
frame_id;
256 twist_cov_t->twist = twist_cov;
258 twist_pub.
publish(twist_cov_t);
261 else if (yaw_initialized) {
262 auto odom = boost::make_shared<nav_msgs::Odometry>();
264 odom->header.stamp = time;
268 odom->pose.pose.position.x =
rpose(0);
269 odom->pose.pose.position.y =
rpose(1);
270 odom->pose.pose.position.z = 0.0;
271 odom->pose.pose.orientation = quat;
273 pose_cov_map.block<2, 2>(0, 0) << rpose_cov.block<2, 2>(0, 0);
274 pose_cov_map.block<2, 1>(0, 5) << rpose_cov.block<2, 1>(0, 2);
275 pose_cov_map.block<1, 2>(5, 0) << rpose_cov.block<1, 2>(2, 0);
276 pose_cov_map.block<1, 1>(5, 5) << rpose_cov.block<1, 1>(2, 2);
278 odom->twist = twist_cov;
284 if (tf_send && yaw_initialized) {
285 geometry_msgs::TransformStamped
transform;
287 transform.header.stamp = time;
291 transform.transform.translation.x =
rpose(0);
292 transform.transform.translation.y =
rpose(1);
293 transform.transform.translation.z = 0.0;
295 transform.transform.rotation = quat;
318 double y0 = wheel_offset[0](1);
319 double y1 = wheel_offset[1](1);
320 double a = -wheel_offset[0](0);
321 double dy_inv = 1.0 / (y1 - y0);
322 double dt_inv = 1.0 / dt;
325 double theta = (distance[1] - distance[0]) * dy_inv;
327 double L = (y1 * distance[0] - y0 * distance[1]) * dy_inv;
330 Eigen::Vector3d v(L, a * theta, theta);
342 double cos_theta = std::cos(theta);
343 double sin_theta = std::sin(theta);
346 if (std::abs(theta) > 1.
e-5) {
347 p = sin_theta / theta;
348 q = (1.0 - cos_theta) / theta;
363 Eigen::Vector3d dpose = M * v;
366 double cy = std::cos(
rpose(2));
367 double sy = std::sin(
rpose(2));
379 rtwist_cov(0) = vel_cov * (y0 * y0 + y1 * y1) * dy_inv * dy_inv;
380 rtwist_cov(1) = vel_cov * a * a * 2.0 * dy_inv * dy_inv + 0.001;
381 rtwist_cov(2) = vel_cov * 2.0 * dy_inv * dy_inv;
387 Eigen::Matrix3d R_yaw;
388 R_yaw << -sy, -cy, 0,
392 Eigen::Vector3d yaw_pose(0, 0, 1);
394 Eigen::Matrix3d J_pose = Eigen::Matrix3d::Identity() + R_yaw * dpose * yaw_pose.transpose();
397 double L_L0 = y1 * dy_inv;
398 double L_L1 = -y0 * dy_inv;
399 double theta_L0 = -dy_inv;
400 double theta_L1 = dy_inv;
402 Eigen::Matrix<double, 3, 2> v_meas;
403 v_meas << L_L0, L_L1,
404 a*theta_L0, a*theta_L1,
407 Eigen::Vector2d theta_meas(theta_L0, theta_L1);
411 if (std::abs(theta) > 1.
e-5) {
412 px = (theta * cos_theta - sin_theta) / (theta * theta);
413 qx = (theta * sin_theta - (1 - cos_theta)) / (theta * theta);
421 Eigen::Matrix3d M_theta;
422 M_theta << px, -qx, 0,
426 Eigen::Matrix<double, 3, 2> J_meas = R * (M * v_meas + M_theta * v * theta_meas.transpose());
429 double L0_cov = vel_cov * dt * dt;
430 double L1_cov = vel_cov * dt * dt;
431 Eigen::Matrix2d meas_cov;
432 meas_cov << L0_cov, 0,
436 rpose_cov = J_pose * rpose_cov * J_pose.transpose() + J_meas * meas_cov * J_meas.transpose();
448 int nwheels = std::min(2, (
int)distance.size());
469 count_meas = measurement.size();
470 measurement_prev.resize(count_meas);
471 count = std::min(count, count_meas);
474 else if (time == time_prev) {
488 std::vector<double> distance(std::max(2, count));
491 for (
int i = 0; i <
count; i++) {
492 double RPM_2_SPEED = wheel_radius[i] * 2.0 * M_PI / 60.0;
493 double rpm = 0.5 * (measurement[i] + measurement_prev[i]);
494 distance[i] = rpm * RPM_2_SPEED * dt;
499 for (
int i = 0; i <
count; i++)
500 distance[i] = measurement[i] - measurement_prev[i];
506 distance[1] = distance[0];
517 std::copy_n(measurement.begin(), measurement.size(), measurement_prev.begin());
528 void handle_rpm(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RPM &rpm)
535 auto rpm_msg = boost::make_shared<mavros_msgs::WheelOdomStamped>();
537 rpm_msg->header.stamp = timestamp;
538 rpm_msg->data.resize(2);
539 rpm_msg->data[0] = rpm.rpm1;
540 rpm_msg->data[1] = rpm.rpm2;
547 std::vector<double> measurement{rpm.rpm1, rpm.rpm2};
561 if (wheel_dist.count == 0)
567 ros::Time timestamp_int =
ros::Time(wheel_dist.time_usec / 1000000UL, 1000UL * (wheel_dist.time_usec % 1000000UL));
571 auto wheel_dist_msg = boost::make_shared<mavros_msgs::WheelOdomStamped>();
573 wheel_dist_msg->header.stamp = timestamp;
574 wheel_dist_msg->data.resize(wheel_dist.count);
575 std::copy_n(wheel_dist.distance.begin(), wheel_dist.count, wheel_dist_msg->data.begin());
577 dist_pub.
publish(wheel_dist_msg);
582 std::vector<double> measurement(wheel_dist.count);
583 std::copy_n(wheel_dist.distance.begin(), wheel_dist.count, measurement.begin());
Eigen::Vector3d rpose
Robot origin 2D-state (SI units)
bool twist_send
send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
std::string format(const std::string &fmt, Args ... args)
OM odom_mode
odometry computation mode
int count_meas
number of wheels in measurements
#define ROS_INFO_NAMED(name,...)
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
#define ROS_WARN_NAMED(name,...)
geometry_msgs::Quaternion get_attitude_orientation_enu()
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/ardupilotm...
ros::Time time_prev
timestamp of previous measurement
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
use wheel's cumulative distance
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
std::vector< Eigen::Vector2d > wheel_offset
wheel x,y offsets (m,NED)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW WheelOdometryPlugin()
Subscriptions get_subscriptions() override
std::string tf_child_frame_id
frame for TF and Pose
std::string frame_id
origin frame for topic headers
tf2_ros::TransformBroadcaster tf2_broadcaster
bool raw_send
send wheel's RPM and cumulative distance
std::string tf_frame_id
origin for TF
std::vector< double > wheel_radius
wheel radiuses (m)
Eigen::Vector3d rtwist
twist (vx, vy, vyaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
std::vector< double > measurement_prev
previous measurement
int count
requested number of wheels to compute odometry
void process_measurement(std::vector< double > measurement, bool rpm, ros::Time time, ros::Time time_pub)
Process wheel measurement.
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Eigen::Matrix3d rpose_cov
pose error 1-var
void update_odometry_diffdrive(std::vector< double > distance, double dt)
Update odometry for differential drive robot. Odometry is computed for robot's origin (IMU)...
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool yaw_initialized
initial yaw initialized (from IMU)
std::string child_frame_id
body-fixed frame for topic headers
bool hasParam(const std::string &key) const
void publish_odometry(ros::Time time)
Publish odometry. Odometry is computed from the very start but no pose info is published until we hav...
double vel_cov
wheel velocity measurement error 1-var (m/s)
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Eigen::Vector3d rtwist_cov
twist error 1-var (vx_cov, vy_cov, vyaw_cov)
std::vector< HandlerInfo > Subscriptions
double quaternion_get_yaw(const Eigen::Quaterniond &q)
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.
OM
Odometry computation modes.
void initialize(UAS &uas_) override
void initialize(UAS &uas_) override
sensor_msgs::Imu::Ptr get_attitude_imu_enu()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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).