diff --git a/rm_orientation_controller/include/rm_orientation_controller/orientation_controller.h b/rm_orientation_controller/include/rm_orientation_controller/orientation_controller.h index b03ac226..99753ee3 100644 --- a/rm_orientation_controller/include/rm_orientation_controller/orientation_controller.h +++ b/rm_orientation_controller/include/rm_orientation_controller/orientation_controller.h @@ -25,7 +25,6 @@ class Controller : public controller_interface::MultiInterfaceControllerget()->getHandle(name); robot_state_ = robot_hw->get()->getHandle("robot_state"); @@ -39,14 +41,45 @@ void Controller::update(const ros::Time& time, const ros::Duration& period) source2target.header.stamp.nsec += 1; // Avoid redundant timestamp source2target_msg_.header.stamp = time; source2target_msg_.header.stamp.nsec += 1; + source2target_msg_ = getTransform(ros::Time(0), source2target, imu_sensor_.getOrientation()[0], imu_sensor_.getOrientation()[1], imu_sensor_.getOrientation()[2], imu_sensor_.getOrientation()[3]) ? source2target : source2target_msg_; robot_state_.setTransform(source2target_msg_, "rm_orientation_controller"); + if (!receive_imu_msg_) tf_broadcaster_.sendTransform(source2target_msg_); + + if (!init_calibration && forced_calibration) + { + try + { + tf2::Transform calibration_tf; + geometry_msgs::TransformStamped tf_msg; + tf_msg = robot_state_.lookupTransform("base_link", "odom", time); + tf2::fromMsg(tf_msg.transform, calibration_tf); + tf2::Matrix3x3 m(calibration_tf.getRotation()); + m.getRPY(cal_roll, cal_pitch, cal_yaw); + getCalTimes++; + if (abs(cal_roll) > 0.1 || abs(cal_pitch) > 0.1) + { + init_calibration = true; + ROS_INFO_THROTTLE(0.1, "Forced calibrate success"); + } + if (getCalTimes > 30) + { + forced_calibration = false; + ROS_INFO_THROTTLE(0.1, "Forced calibrate failed"); + } + } + catch (tf2::TransformException& ex) + { + init_calibration = false; + ROS_WARN("%s", ex.what()); + } + } } } @@ -74,8 +107,17 @@ bool Controller::getTransform(const ros::Time& time, geometry_msgs::TransformSta } tf2::Quaternion odom2fixed_quat; odom2fixed_quat.setValue(x, y, z, w); + if (forced_calibration && init_calibration) + { + double ori_roll, ori_pitch, ori_yaw; + tf2::Matrix3x3 m1(odom2fixed_quat); + m1.getRPY(ori_roll, ori_pitch, ori_yaw); + odom2fixed_quat.setRPY(ori_roll + cal_roll, ori_pitch + cal_pitch, ori_yaw); + odom2fixed_quat.normalize(); + } odom2fixed.setRotation(odom2fixed_quat); source2target.transform = tf2::toMsg(source2odom * odom2fixed * fixed2target); + return true; }