diff --git a/CMakeLists.txt b/CMakeLists.txt index 6f4bc7d..61134aa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -61,3 +61,17 @@ target_link_libraries(rf2o_laser_odometry_node ${EIGEN_LIBRARIES} ${MRPT_LIBS} ) + +############# +## Install ## +############# + +install(TARGETS rf2o_laser_odometry_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/src/CLaserOdometry2D.cpp b/src/CLaserOdometry2D.cpp index 60e2ee5..6607506 100644 --- a/src/CLaserOdometry2D.cpp +++ b/src/CLaserOdometry2D.cpp @@ -282,7 +282,7 @@ void CLaserOdometry2D::odometryCalculation() } m_runtime = 1000*m_clock.Tac(); - ROS_INFO("Time odometry (ms): %f", m_runtime); + ROS_DEBUG("Time odometry (ms): %f", m_runtime); //Update poses PoseUpdate(); @@ -950,7 +950,7 @@ void CLaserOdometry2D::PoseUpdate() kai_loc_old(2) = kai_abs(2); - ROS_INFO("LASERodom = [%f %f %f]",laser_pose.x(),laser_pose.y(),laser_pose.yaw()); + ROS_DEBUG("LASERodom = [%f %f %f]",laser_pose.x(),laser_pose.y(),laser_pose.yaw()); // GET ROBOT POSE from LASER POSE @@ -981,7 +981,7 @@ void CLaserOdometry2D::PoseUpdate() //Compose Transformations robot_pose = laser_pose + LaserPoseOnTheRobot_inv; - ROS_INFO("BASEodom = [%f %f %f]",robot_pose.x(),robot_pose.y(),robot_pose.yaw()); + ROS_DEBUG("BASEodom = [%f %f %f]",robot_pose.x(),robot_pose.y(),robot_pose.yaw()); // Estimate linear/angular speeds (mandatory for base_local_planner)