Skip to content

Commit

Permalink
Extracted laser odometry component into own class.
Browse files Browse the repository at this point in the history
* Let transformToEnd transform a whole cloud at once instead of only one point, since it was only called in loops over whole clouds.
* Reduced scopes of variables where possible.

Changes to the logic:
* Do not publish corner and surface clouds during initialization, as they are anyhow rejected without the corresponding full resolution cloud (which was not sent during initialization).

New Features:
* All buffers used during optimization are now dynamic and automatically adapted to the currently processed cloud sizes.
* Again, there are two modis: active and passive. However, passive mode requires some further work with respect to result management.
  • Loading branch information
StefanGlaser committed Dec 1, 2017
1 parent 40ac7a1 commit 5fe0300
Show file tree
Hide file tree
Showing 8 changed files with 1,130 additions and 860 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ add_subdirectory(src/lib)
add_executable(scanRegistration src/velodyne_scan_registration_node.cpp)
target_link_libraries(scanRegistration ${catkin_LIBRARIES} ${PCL_LIBRARIES} loam )

add_executable(laserOdometry src/laserOdometry.cpp)
target_link_libraries(laserOdometry ${catkin_LIBRARIES} ${PCL_LIBRARIES} )
add_executable(laserOdometry src/laser_odometry_node.cpp)
target_link_libraries(laserOdometry ${catkin_LIBRARIES} ${PCL_LIBRARIES} loam )

add_executable(laserMapping src/laserMapping.cpp)
target_link_libraries(laserMapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} )
Expand Down
856 changes: 0 additions & 856 deletions src/laserOdometry.cpp

This file was deleted.

20 changes: 20 additions & 0 deletions src/laser_odometry_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#include <ros/ros.h>
#include "lib/LaserOdometry.h"


/** Main node entry point. */
int main(int argc, char **argv)
{
ros::init(argc, argv, "laserOdometry");
ros::NodeHandle node;
ros::NodeHandle privateNode("~");

loam::LaserOdometry laserOdom(0.1);

if (laserOdom.setup(node, privateNode)) {
// initialization successful
laserOdom.spin();
}

return 0;
}
4 changes: 3 additions & 1 deletion src/lib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,7 @@ add_library(loam
ScanRegistration.h
ScanRegistration.cpp
VelodyneScanRegistration.h
VelodyneScanRegistration.cpp)
VelodyneScanRegistration.cpp
LaserOdometry.h
LaserOdometry.cpp)
target_link_libraries(loam ${catkin_LIBRARIES} ${PCL_LIBRARIES})
Loading

0 comments on commit 5fe0300

Please sign in to comment.