Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions devel/core_algorithm/fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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_align<this->max_dt_align && dt_align>this->min_dt_align)
Expand Down Expand Up @@ -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_align<this->max_dt_align && dt_align>this->min_dt_align)
Expand Down Expand Up @@ -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_align<this->max_dt_align && dt_align>this->min_dt_align)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it's in wheel callback so actually the variable name should be wheel_time

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;
Expand All @@ -90,13 +87,6 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg)
double dt = odom_time - this->prev_odom_time;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

also replace all the variables from odom to wheel. the reason is that odometry is a method which calculates relative pose tracking and is not limited to wheel information.

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;

Expand All @@ -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;
Expand All @@ -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);
Expand Down