Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

correct laser pose update according to neomanic repo and handle INF laser data. #24

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
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
6 changes: 3 additions & 3 deletions src/CLaserOdometry2D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ void CLaserOdometry2D::init(const sensor_msgs::LaserScan& scan,
kai_loc_old_ = MatrixS31::Zero();

module_initialized = true;
last_odom_time = ros::Time::now();
last_odom_time = scan.header.stamp;
}

const CLaserOdometry2D::Pose3d& CLaserOdometry2D::getIncrement() const
Expand Down Expand Up @@ -292,7 +292,7 @@ void CLaserOdometry2D::createImagePyramid()
//Inner pixels
if ((u>1)&&(u<cols_i-2))
{
if (dcenter > 0.f)
if (std::isfinite(dcenter) && dcenter > 0.f)
{
float sum = 0.f;
float weight = 0.f;
Expand All @@ -316,7 +316,7 @@ void CLaserOdometry2D::createImagePyramid()
//Boundary
else
{
if (dcenter > 0.f)
if (std::isfinite(dcenter) && dcenter > 0.f)
{
float sum = 0.f;
float weight = 0.f;
Expand Down
10 changes: 5 additions & 5 deletions src/CLaserOdometry2DNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,6 @@ CLaserOdometry2DNode::CLaserOdometry2DNode() :
initial_robot_pose.pose.pose.orientation.z = 0;
}

setLaserPoseFromTf();

//Init variables
module_initialized = false;
Expand Down Expand Up @@ -196,6 +195,7 @@ void CLaserOdometry2DNode::LaserCallBack(const sensor_msgs::LaserScan::ConstPtr&
}
else
{
setLaserPoseFromTf();
init(last_scan, initial_robot_pose.pose.pose);
first_laser_scan = false;
}
Expand All @@ -218,9 +218,9 @@ void CLaserOdometry2DNode::publish()
//---------------------------------------
if (publish_tf)
{
//ROS_INFO("[rf2o] Publishing TF: [base_link] to [odom]");
ROS_DEBUG("[rf2o] Publishing TF: [base_link] to [odom]");
geometry_msgs::TransformStamped odom_trans;
odom_trans.header.stamp = ros::Time::now();
odom_trans.header.stamp = last_odom_time;
odom_trans.header.frame_id = odom_frame_id;
odom_trans.child_frame_id = base_frame_id;
odom_trans.transform.translation.x = robot_pose_.translation()(0);
Expand All @@ -233,9 +233,9 @@ void CLaserOdometry2DNode::publish()

//next, we'll publish the odometry message over ROS
//-------------------------------------------------
//ROS_INFO("[rf2o] Publishing Odom Topic");
ROS_DEBUG ("[rf2o] Publishing Odom Topic");
nav_msgs::Odometry odom;
odom.header.stamp = ros::Time::now();
odom.header.stamp = last_odom_time;
odom.header.frame_id = odom_frame_id;
//set the position
odom.pose.pose.position.x = robot_pose_.translation()(0);
Expand Down