Skip to content

Commit

Permalink
potential fix
Browse files Browse the repository at this point in the history
  • Loading branch information
petrlmat committed Jan 10, 2024
1 parent 4ff11bc commit 1b7a989
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 2 deletions.
3 changes: 3 additions & 0 deletions config/default.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# Subtract the first pose from all msgs so that the origin is in zero (OpenVINS sometimes starts rotated by pi/2)
init_in_zero: true

rate_limiter:
enabled: true
max_rate: 100.0 # [Hz]
25 changes: 23 additions & 2 deletions src/VinsRepublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <mrs_lib/mutex.h>
#include <mrs_lib/attitude_converter.h>
#include <mrs_lib/msg_extractor.h>
#include <mrs_lib/geometry/conversions.h>

#include <nodelet/nodelet.h>

Expand Down Expand Up @@ -50,6 +51,11 @@ class VinsRepublisher : public nodelet::Nodelet {
std::string _mrs_vins_world_frame_;
std::string _vins_fcu_frame_;
double _rate_limiter_rate_;
bool _init_in_zero_;

bool got_init_pose_ = false;
Eigen::Vector3d init_position_eigen_;
Eigen::Quaterniond init_orientation_eigen_;

bool validateOdometry(const nav_msgs::Odometry &odometry);

Expand Down Expand Up @@ -101,6 +107,8 @@ void VinsRepublisher::onInit() {
param_loader.loadParam("mrs_vins_world_frame", _mrs_vins_world_frame_);
param_loader.loadParam("vins_fcu_frame", _vins_fcu_frame_);

param_loader.loadParam("init_in_zero", _init_in_zero_);

if (!param_loader.loadedSuccessfully()) {
ROS_ERROR("[%s]: parameter loading failure", node_name.c_str());
ros::shutdown();
Expand Down Expand Up @@ -229,7 +237,8 @@ void VinsRepublisher::odometryCallback(const nav_msgs::OdometryConstPtr &odom) {

geometry_msgs::PoseStamped vins_pose;
vins_pose.header = odom->header;
vins_pose.pose = mrs_lib::getPose(odom);

vins_pose.pose = mrs_lib::getPose(odom);

geometry_msgs::Vector3Stamped vins_velocity;
vins_velocity.header = odom->header;
Expand Down Expand Up @@ -304,7 +313,6 @@ void VinsRepublisher::odometryCallback(const nav_msgs::OdometryConstPtr &odom) {
/* transform the vins velocity to mrs_world_frame //{ */

{

auto res = transformer_.transform(vins_velocity, tf);

if (!res) {
Expand Down Expand Up @@ -369,6 +377,19 @@ void VinsRepublisher::odometryCallback(const nav_msgs::OdometryConstPtr &odom) {

/* //} */

// save initial pose to subtract it from all messages to compensate initialized orientation ambiguity
if (_init_in_zero_ && !got_init_pose_) {
init_position_eigen_ = mrs_lib::geometry::toEigen(vins_pose_mrs_world.pose.position);
init_orientation_eigen_ = mrs_lib::geometry::toEigen(vins_pose_mrs_world.pose.orientation).inverse();
got_init_pose_ = true;
}

// compensate initialized orientation ambiguity
vins_pose_mrs_world.pose.position =
mrs_lib::geometry::fromEigen(init_orientation_eigen_ * (mrs_lib::geometry::toEigen(vins_pose_mrs_world.pose.position) - init_position_eigen_));
vins_pose_mrs_world.pose.orientation =
mrs_lib::geometry::fromEigen(mrs_lib::geometry::toEigen(vins_pose_mrs_world.pose.orientation) * init_orientation_eigen_);

// fill the new transformed odom message
nav_msgs::Odometry odom_trans;

Expand Down

0 comments on commit 1b7a989

Please sign in to comment.