diff --git a/devel/core_algorithm/fusion/src/fusion_node.cpp b/devel/core_algorithm/fusion/src/fusion_node.cpp index 9764ede..e0dbe22 100644 --- a/devel/core_algorithm/fusion/src/fusion_node.cpp +++ b/devel/core_algorithm/fusion/src/fusion_node.cpp @@ -130,7 +130,7 @@ void FusionNode::initCallback(const geometry_msgs::msg::PoseWithCovariance & ini void FusionNode::localCallback(const nav_msgs::msg::Odometry & local_msg){ rclcpp::Time stamp = local_msg.header.stamp; - this->prev_pred_time = stamp.seconds()+stamp.nanoseconds()*1e-9; + this->prev_pred_time = stamp.nanoseconds()*1e-9; Eigen::Vector3d local_pose; double local_yaw = utils::qua2yaw(local_msg.pose.pose.orientation); @@ -177,7 +177,7 @@ void FusionNode::globalCallback(const geometry_msgs::msg::PoseWithCovarianceStam if(if_align){ rclcpp::Clock clock; rclcpp::Time stamp = clock.now(); - double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9; + double corr_time = stamp.nanoseconds()*1e-9; double dt_align = corr_time-this->prev_pred_time; if(dt_alignmax_dt_align && dt_align>this->min_dt_align) @@ -232,7 +232,7 @@ void FusionNode::cbCameraCallback(const geometry_msgs::msg::PoseStamped & cbcam_ if(if_align){ rclcpp::Clock clock; rclcpp::Time stamp = clock.now(); - double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9; + double corr_time = stamp.nanoseconds()*1e-9; double dt_align = corr_time-this->prev_pred_time; if(dt_alignmax_dt_align && dt_align>this->min_dt_align) @@ -287,7 +287,7 @@ void FusionNode::obCameraCallback(const geometry_msgs::msg::PoseStamped & obcam_ if(if_align){ rclcpp::Clock clock; rclcpp::Time stamp = clock.now(); - double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9; + double corr_time = stamp.nanoseconds()*1e-9; double dt_align = corr_time-this->prev_pred_time; if(dt_alignmax_dt_align && dt_align>this->min_dt_align) diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp b/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp index 44ef358..beb5253 100644 --- a/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp +++ b/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp @@ -31,8 +31,6 @@ class WioNode : public rclcpp::Node{ std::string robot_parent_frame; std::string robot_frame; - Eigen::Vector3d prev_wheel_pose; - Eigen::Vector3d d_position; Eigen::Vector3d local_pose; Eigen::Vector3d local_twist; Eigen::Matrix3d local_pose_cov; diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp b/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp index d7d744a..f75a603 100644 --- a/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp +++ b/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp @@ -15,8 +15,6 @@ WioNode::WioNode() : Node("wio_node"){ for(int i=0; i<3; i++) this->pose_cov_min[i] = 0; this->first_odom_cb = true; this->prev_odom_time = 0.0; - this->prev_wheel_pose.setZero(); - this->d_position.setZero(); this->local_pose.setZero(); this->local_twist.setZero(); this->local_pose_cov.setIdentity(); @@ -77,11 +75,10 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg) { rclcpp::Clock clock; rclcpp::Time stamp = clock.now(); - double odom_time = stamp.seconds() + stamp.nanoseconds() * 1e-9; - + double odom_time = stamp.nanoseconds() * 1e-9; + if (this->first_odom_cb) { - this->prev_wheel_pose << wheel_msg.angular.x, wheel_msg.angular.y, 0.0; this->prev_odom_time = odom_time; this->first_odom_cb = false; return; @@ -90,13 +87,6 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg) double dt = odom_time - this->prev_odom_time; this->prev_odom_time = odom_time; - - this->d_position << wheel_msg.angular.x-this->prev_wheel_pose(0), - wheel_msg.angular.y-this->prev_wheel_pose(1), - 0.0; - - this->prev_wheel_pose << wheel_msg.angular.x, wheel_msg.angular.y, 0.0; - this->local_twist(0) = wheel_msg.linear.x; this->local_twist(1) = wheel_msg.linear.y; @@ -115,7 +105,7 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg) void WioNode::imuCallback(const sensor_msgs::msg::Imu & imu_msg) { rclcpp::Time stamp = imu_msg.header.stamp; - double time = stamp.seconds()+stamp.nanoseconds()*1e-9; + double time = stamp.nanoseconds()*1e-9; if(this->first_imu_cb){ this->prev_imu_time = time; @@ -126,18 +116,17 @@ void WioNode::imuCallback(const sensor_msgs::msg::Imu & imu_msg) double dt = time-this->prev_imu_time; this->prev_imu_time = time; - this->local_twist(2) = imu_msg.angular_velocity.z; this->local_pose(2) = - utils::angleNormalizing(this->local_pose(2)+0.5*this->local_twist(2)*dt); + utils::angleNormalizing(this->local_pose(2)+this->local_twist(2)*dt); Eigen::Matrix3d R; R << cos(this->local_pose(2)), -sin(this->local_pose(2)), 0.0, sin(this->local_pose(2)), cos(this->local_pose(2)), 0.0, 0.0, 0.0, 0.0; - this->local_pose += R*this->d_position; + this->local_pose += R*this->local_twist*dt; // publish odometry pubLocalPose(stamp);