mirror of
https://github.com/MAPIRlab/rf2o_laser_odometry.git
synced 2023-04-06 19:28:55 +08:00
@@ -16,7 +16,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
## System dependencies are found with CMake's conventions
|
||||
find_package(Boost REQUIRED COMPONENTS system)
|
||||
find_package(cmake_modules REQUIRED)
|
||||
find_package(Eigen REQUIRED)
|
||||
find_package(Eigen3 REQUIRED)
|
||||
find_package(MRPT REQUIRED base obs maps slam)
|
||||
#include_directories(${MRPT_INCLUDE_DIRS})
|
||||
#MESSAGE( STATUS "MRPT_INCLUDE_DIRS: " ${MRPT_INCLUDE_DIRS})
|
||||
@@ -38,7 +38,7 @@ catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES laser_odometry
|
||||
CATKIN_DEPENDS nav_msgs roscpp sensor_msgs std_msgs tf
|
||||
DEPENDS system_lib
|
||||
#DEPENDS system_lib
|
||||
)
|
||||
|
||||
## Specify additional locations of header files
|
||||
|
||||
@@ -80,7 +80,7 @@ void CLaserOdometry2D::Init()
|
||||
tf::StampedTransform transform;
|
||||
try
|
||||
{
|
||||
tf_listener.lookupTransform("/base_link", last_scan.header.frame_id, ros::Time(0), transform);
|
||||
tf_listener.lookupTransform(base_frame_id, last_scan.header.frame_id, ros::Time(0), transform);
|
||||
}
|
||||
catch (tf::TransformException &ex)
|
||||
{
|
||||
@@ -918,7 +918,7 @@ void CLaserOdometry2D::PoseUpdate()
|
||||
tf::StampedTransform transform;
|
||||
try
|
||||
{
|
||||
tf_listener.lookupTransform(last_scan.header.frame_id, "/base_link", ros::Time(0), transform);
|
||||
tf_listener.lookupTransform(last_scan.header.frame_id, base_frame_id, ros::Time(0), transform);
|
||||
}
|
||||
catch (tf::TransformException &ex)
|
||||
{
|
||||
@@ -978,8 +978,8 @@ void CLaserOdometry2D::PoseUpdate()
|
||||
//---------------------------------------
|
||||
geometry_msgs::TransformStamped odom_trans;
|
||||
odom_trans.header.stamp = ros::Time::now();
|
||||
odom_trans.header.frame_id = odom_frame_id;
|
||||
odom_trans.child_frame_id = base_frame_id;
|
||||
odom_trans.header.frame_id = base_frame_id;
|
||||
odom_trans.child_frame_id = odom_frame_id;
|
||||
odom_trans.transform.translation.x = robot_pose.x();
|
||||
odom_trans.transform.translation.y = robot_pose.y();
|
||||
odom_trans.transform.translation.z = 0.0;
|
||||
|
||||
Reference in New Issue
Block a user