Skip to content

Commit

Permalink
publish bias only in odometry handler
Browse files Browse the repository at this point in the history
  • Loading branch information
petrlmat committed Feb 16, 2024
1 parent 03daf8d commit bc324f3
Showing 1 changed file with 0 additions and 16 deletions.
16 changes: 0 additions & 16 deletions src/imuPreintegration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -589,22 +589,6 @@ namespace liosam
odometry->twist.twist.angular.z = thisImu.angular_velocity.z + prevBiasOdom_.gyroscope().z();
pubPreOdometry.publish(odometry);

geometry_msgs::Vector3Stamped accBiasMsg;
accBiasMsg.header.stamp = ros::Time::now();
accBiasMsg.header.frame_id = "fcu";
accBiasMsg.vector.x = prevBiasOdom_.accelerometer().x();
accBiasMsg.vector.y = prevBiasOdom_.accelerometer().y();
accBiasMsg.vector.z = prevBiasOdom_.accelerometer().z();
pubLinAccBias.publish(accBiasMsg);

geometry_msgs::Vector3Stamped gyroBiasMsg;
gyroBiasMsg.header.stamp = ros::Time::now();
gyroBiasMsg.header.frame_id = "fcu";
gyroBiasMsg.vector.x = prevBiasOdom_.gyroscope().x();
gyroBiasMsg.vector.y = prevBiasOdom_.gyroscope().y();
gyroBiasMsg.vector.z = prevBiasOdom_.gyroscope().z();
pubAngVelBias.publish(gyroBiasMsg);

}
/*//}*/
};
Expand Down

0 comments on commit bc324f3

Please sign in to comment.