Skip to content

Commit

Permalink
extras: odom: update velocity covariance fields from 'twist' to 'velo…
Browse files Browse the repository at this point in the history
…city_covariance'
  • Loading branch information
TSC21 authored and vooon committed Mar 6, 2019
1 parent 692afa4 commit 567cdb2
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions mavros_extras/src/plugins/odom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ class OdometryPlugin : public plugin::PluginBase {

//! Build 6x6 velocity covariance matrix to be transformed and sent
Matrix6d cov_vel = Matrix6d::Zero();
ftf::mavlink_urt_to_covariance_matrix(odom_msg.twist_covariance, cov_vel);
ftf::mavlink_urt_to_covariance_matrix(odom_msg.velocity_covariance, cov_vel);

Eigen::Vector3d position {}; //!< Position vector. WRT frame_id
Eigen::Quaterniond orientation {}; //!< Attitude quaternion. WRT frame_id
Expand Down Expand Up @@ -408,7 +408,7 @@ class OdometryPlugin : public plugin::PluginBase {

ftf::quaternion_to_mavlink(orientation, msg.q);
ftf::covariance_urt_to_mavlink(cov_pose_map, msg.pose_covariance);
ftf::covariance_urt_to_mavlink(cov_vel_map, msg.twist_covariance);
ftf::covariance_urt_to_mavlink(cov_vel_map, msg.velocity_covariance);

// send ODOMETRY msg
UAS_FCU(m_uas)->send_message_ignore_drop(msg);
Expand Down

0 comments on commit 567cdb2

Please sign in to comment.