# **Soter Local Localization** Local localization(pose tracking) by laserscan(lidar) and odometry, also needs map input. **** ## <font color=#FF0000>soter_local_localization_node</font> **** ![](https://i.imgur.com/IvkNtgd.png) ### Published topics: * **~scan** ( sensor_msgs/PointCloud2 ) Laserscan republished on map frame. * **~scan_down** ( sensor_msgs/PointCloud2 ) Laserscan downsampled republished on map frame. * **~potential_map** ( nav_msgs/OccupancyGrid ) Pub potential map if using gauss-newton. * **~map_cloud** ( sensor_msgs/PointCloud2 ) Map cloud from occupancy grid map if using icp. * **~submap_cloud** ( sensor_msgs/PointCloud2 ) Submap cloud cutted from whole map cloud if using icp. ### Subscribed Topics: * **map_topic(from parameter setting)** ( nav_msgs/OccupancyGrid ) Map input for localization. * **scan_topic(from parameter setting)** ( sensor_msgs/LaserScan ) Scan input if use_cloud_input is false. * **scan_cloud_topic(from parameter setting)** ( sensor_msgs/PointCloud2 ) Scan input if use_cloud_input is true. * **odom_topic(from parameter setting)** ( nav_msgs/Odometry ) Odom input if use_odom_input is true and odom_by_tf is false. * **/initialpose** ( geometry_msgs::PoseWithCovarianceStamped ) For setting initial guess. ### Parameters * **~map_topic:** (string, default:"/map") Map topic to be subscribed. * **~use_cloud_input:** (bool, default: false) Whether using laser cloud input(2d). * **~scan_topic:** (string, default:"/scan") Scan topic to be subscribed if use_cloud_input is false. * **~scan_cloud_topic:** (string, default:"/merged_cloud") Scan cloud topic to be subscribed if use_cloud_input is true. * #### Odometry input for scan matching initial guess * **~use_odom_input:** (bool, default: true) Whether using odometry as initial guess(no matter by tf tree or odom topic). If set to false, then just use laserscan to do localization. * **~odom_by_tf:** (bool, default: true) If set to true, then get initial guess from tf tree(If use_odom_input is true). If set to false, then get initial guess from odom topic. * **~odom_topic:** (string, default:"odom") Odom topic to be subscribed if using odom input and odom_by_tf is false. * **~odom_frame_id:** (string, default:"odom") For getting initial guess from tf tree if using odom input and odom_by_tf is true. * **~robot_frame_id:** (string, default:"base_link") For getting initial guess from tf tree if using odom input and odom_by_tf is true. And is also needed for transform laserscan from laser frame to robot frame * **~published_frame_id:** (string, default:"odom") Final localization result will be replaced by transform from map to published frame. * **~transform_tolerance:** (double, default: 0.1) Tf listener tolerance. * **~transform_offset:** (double, default: 0.1) For publishing tf in the future (for navigation). * **~update_min_d:** (double, default: 0.02) Do scan matching only when over this threshold(translation, if use odom). * **~update_min_a:** (double, default: 0.02) Do scan matching only when over this threshold(rotation, if use odom). * **~halt_check_count:** (int, default: 10) If over this count times not over update_min_a or update_min_a, then stop doing scan matching, just trust odom input * #### Laserscan processor * **~laser_min_range:** (double, default: -1) -1 for using scan msg default setting. * **~laser_max_range:** (double, default: -1) -1 for using scan msg default setting. * **~voxel_size:** (double, default: 0.2) Voxel filter for downsample * **~max_laser_points:** (int, default: 100) Downsmaple after voxel filter. * #### Scan matching * **~scan_matching/scan_matching_method** (int, default: 1) Scan matching method selection, 1 for gauss_newton, 2 for icp * #### Gauss Newton * **~scan_matching/gauss_newton/potential_map_resolution** (double, default: 0.05) Potential map resolution. * **~scan_matching/gauss_newton/likelihood_sigma** (double, default: 0.1) For smoothing potential map and make it differentiable. * **~scan_matching/gauss_newton/likelihood_max_dist** (double, default: 0.3) For smoothing potential map and make it differentiable. * **~scan_matching/gauss_newton/max_iteration** (int, default: 100) Max iteration for gauss newton optimization. * **~scan_matching/gauss_newton/step_size_scalar** (double, default: 0.1) Slow down convergence speed. * #### ICP * **~scan_matching/icp/submap_size** (double, default: 10.0) Cloud size of submap cutted from whole map. * **~scan_matching/icp/submap_voxel_size** (double, default: 0.05) For submap cloud downsample. * **~scan_matching/icp/one_pixel_to_four_points** (bool, default: false) Whether creating four points from one pixel for more accurate scan matching (higher compute error). * **~scan_matching/icp/update_submap_dis** (double, default: 1.0) Update submap cloud when moving over this distance. * **~scan_matching/icp/max_iteration** (int, default: 100) Max iteration of icp. * **~scan_matching/icp/max_correspondence_distance** (double, default: 0.05) Max correspondence distance after initial stage. * **~scan_matching/icp/max_correspondence_distance_init** (double, default: 0.2) Max correspondence distance for initial stage. * **~scan_matching/icp/transformation_epsilon** (double, default: 1e-10) Transformation epsilon. * **~scan_matching/icp/euclidean_fitness_epsilon** (double, default: 0.1) Euclidean fitness epsilon. **** # **Demo Video** ITRI lab test [![ITRI lab test](http://img.youtube.com/vi/m0GKIkiNgxI/0.jpg)](https://www.youtube.com/watch?v=m0GKIkiNgxI&feature=youtu.be&ab_channel=%E6%9E%97%E6%94%BF%E7%A2%A9 "ITRI lab test") ITRI dining room [![ITRI lab test](http://img.youtube.com/vi/t4g4w9aQLjk/0.jpg)](https://www.youtube.com/watch?v=t4g4w9aQLjk&feature=youtu.be&ab_channel=%E6%9E%97%E6%94%BF%E7%A2%A9 "ITRI dining room")