Skip to content
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
28 changes: 23 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,19 +53,37 @@ set(DEPENDENCIES
"nav_msgs"
)
ament_target_dependencies(${EXECUTABLE_NAME} ${DEPENDENCIES})

## Declare a cpp library
add_library(${PROJECT_NAME} src/CLaserOdometry2D.cpp)
add_library(${PROJECT_NAME} SHARED src/CLaserOdometry2D.cpp)

## Declare a cpp executable
ament_target_dependencies(${PROJECT_NAME} ${DEPENDENCIES})

install(TARGETS ${EXECUTABLE_NAME}
DESTINATION lib/${PROJECT_NAME})
install(TARGETS ${EXECUTABLE_NAME} ${PROJECT_NAME}
DESTINATION lib)

install(TARGETS ${PROJECT_NAME}
DESTINATION ../sha32_driver/lib)

install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME})

ament_package()
install(DIRECTORY
include
DESTINATION .
)

install(
TARGETS ${PROJECT_NAME}
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

ament_export_include_directories(include)

ament_export_targets(export_${PROJECT_NAME})

ament_package()
22 changes: 11 additions & 11 deletions src/CLaserOdometry2D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,8 +251,8 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::msg::LaserScan& sc

auto m_runtime = get_clock()->now() - start;

RCLCPP_INFO(get_logger(), "[rf2o] execution time (ms): %f",
m_runtime.seconds()*double(1000));
// RCLCPP_INFO(get_logger(), "[rf2o] execution time (ms): %f",
// m_runtime.seconds()*double(1000));

//Update poses
PoseUpdate();
Expand Down Expand Up @@ -812,7 +812,7 @@ bool CLaserOdometry2D::filterLevelSolution()
Eigen::SelfAdjointEigenSolver<Eigen::MatrixXf> eigensolver(cov_odo);
if (eigensolver.info() != Eigen::Success)
{
RCLCPP_WARN(get_logger(), "[rf2o] ERROR: Eigensolver couldn't find a solution. Pose is not updated");
// RCLCPP_WARN(get_logger(), "[rf2o] ERROR: Eigensolver couldn't find a solution. Pose is not updated");
return false;
}

Expand Down Expand Up @@ -935,18 +935,18 @@ void CLaserOdometry2D::PoseUpdate()
kai_loc_old_(1) = -kai_abs_(0)*std::sin(phi) + kai_abs_(1)*std::cos(phi);
kai_loc_old_(2) = kai_abs_(2);

RCLCPP_INFO(get_logger(), "[rf2o] LASERodom = [%f %f %f]",
laser_pose_.translation()(0),
laser_pose_.translation()(1),
rf2o::getYaw(laser_pose_.rotation()));
// RCLCPP_INFO(get_logger(), "[rf2o] LASERodom = [%f %f %f]",
// laser_pose_.translation()(0),
// laser_pose_.translation()(1),
// rf2o::getYaw(laser_pose_.rotation()));

//Compose Transformations
robot_pose_ = laser_pose_ * laser_pose_on_robot_inv_;

RCLCPP_INFO(get_logger(), "BASEodom = [%f %f %f]",
robot_pose_.translation()(0),
robot_pose_.translation()(1),
rf2o::getYaw(robot_pose_.rotation()));
// RCLCPP_INFO(get_logger(), "BASEodom = [%f %f %f]",
// robot_pose_.translation()(0),
// robot_pose_.translation()(1),
// rf2o::getYaw(robot_pose_.rotation()));

// Estimate linear/angular speeds (mandatory for base_local_planner)
// last_scan -> the last scan received
Expand Down