@@ -2617,40 +2617,42 @@ bool RosFilter<T>::prepareAcceleration(
26172617 // of normal forces, so we use a parameter
26182618 if (remove_gravitational_acceleration_[topic_name]) {
26192619 tf2::Vector3 normAcc (0 , 0 , gravitational_acceleration_);
2620- tf2::Quaternion curAttitude;
26212620 tf2::Transform trans;
26222621
26232622 if (::fabs (msg->orientation_covariance [0 ] + 1 ) < 1e-9 ) {
26242623 // Imu message contains no orientation, so we should use orientation
26252624 // from filter state to transform and remove acceleration
26262625 const Eigen::VectorXd & state = filter_.getState ();
2627- tf2::Vector3 stateTmp (state (StateMemberRoll), state (StateMemberPitch),
2628- state (StateMemberYaw));
2626+ tf2::Matrix3x3 stateTmp;
2627+ stateTmp.setRPY (state (StateMemberRoll),
2628+ state (StateMemberPitch),
2629+ state (StateMemberYaw));
2630+
26292631 // transform state orientation to IMU frame
26302632 tf2::Transform imuFrameTrans;
26312633 ros_filter_utilities::lookupTransformSafe (
2632- tf_buffer_.get (), msg_frame, target_frame , msg->header .stamp , tf_timeout_,
2634+ tf_buffer_.get (), target_frame, msg_frame , msg->header .stamp , tf_timeout_,
26332635 imuFrameTrans);
2634- stateTmp = imuFrameTrans.getBasis () * stateTmp;
2635- curAttitude.setRPY (stateTmp.getX (), stateTmp.getY (), stateTmp.getZ ());
2636+ trans.setBasis (stateTmp * imuFrameTrans.getBasis ());
26362637 } else {
2638+ tf2::Quaternion curAttitude;
26372639 tf2::fromMsg (msg->orientation , curAttitude);
26382640 if (fabs (curAttitude.length () - 1.0 ) > 0.01 ) {
26392641 RCLCPP_WARN_ONCE (
26402642 this ->get_logger (),
26412643 " An input was not normalized, this should NOT happen, but will normalize." );
26422644 curAttitude.normalize ();
26432645 }
2646+ trans.setRotation (curAttitude);
26442647 }
2645- trans.setRotation (curAttitude);
26462648 tf2::Vector3 rotNorm = trans.getBasis ().inverse () * normAcc;
26472649 acc_tmp.setX (acc_tmp.getX () - rotNorm.getX ());
26482650 acc_tmp.setY (acc_tmp.getY () - rotNorm.getY ());
26492651 acc_tmp.setZ (acc_tmp.getZ () - rotNorm.getZ ());
26502652
26512653 RF_DEBUG (
26522654 " Orientation is " <<
2653- curAttitude << " Acceleration due to gravity is " << rotNorm <<
2655+ trans. getRotation () << " Acceleration due to gravity is " << rotNorm <<
26542656 " After removing acceleration due to gravity, acceleration is " <<
26552657 acc_tmp << " \n " );
26562658 }
0 commit comments