ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I have a simple solution for that. First we need to filter to our LidarScan inf values to a range value (e.g 5). and than set this filter scan as a parameter to gmapping.
this is my gmapping node parameters
<launch>
<node pkg="gmapping" type="slam_gmapping" name='gmapping_node' output='log'>
<param name="base_frame" value="base_link"/>
<param name="odom_frame" value="odom"/>
<param name="delta" value="0.02"/>
<param name="xmin" value="-25"/>
<param name="ymin" value="-25"/>
<param name="xmax" value="25"/>
<param name="ymax" value="25"/>
<param name="map_update_interval" value="1"/>
<param name="linearUpdate" value="0.05"/>
<param name="angularUpdate" value="0.05"/>
<param name="temporalUpdate" value="0.1"/>
<param name="particles" value="50"/>
<param name="maxUrange" value="3.4"/>
<param name="maxRange" value="3.6"/>
<remap from="scan" to="/scan_filtered"/>
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter">
<rosparam command="load" file="$(find robot_navigation)/config/lidar_config.yaml"/>
<remap from="base_scan" to="scan"/>
</node> </launch>
and this is my lidar_scan.yaml
scan_filter_chain:
- name: range
type: laser_filters/LaserScanRangeFilter
params:
use_message_range_limits: false
lower_threshold: 0.2
upper_threshold: 3.5
lower_replacement_value: -.inf
upper_replacement_value: 3.5
dont forget to ramap with
<remap from="scan" to="/scan_filtered"/>
2 | No.2 Revision |
I have a simple solution for that. First we need add below parameters to filter to our LidarScan inf values to a range value (e.g 5). and than set this filter scan as a parameter to gmapping.
this is my gmapping node parametersyour costmap_common_params.yaml
<launch>
<node pkg="gmapping" type="slam_gmapping" name='gmapping_node' output='log'>
<param name="base_frame" value="base_link"/>
<param name="odom_frame" value="odom"/>
<param name="delta" value="0.02"/>
<param name="xmin" value="-25"/>
<param name="ymin" value="-25"/>
<param name="xmax" value="25"/>
<param name="ymax" value="25"/>
<param name="map_update_interval" value="1"/>
<param name="linearUpdate" value="0.05"/>
<param name="angularUpdate" value="0.05"/>
<param name="temporalUpdate" value="0.1"/>
<param name="particles" value="50"/>
<param name="maxUrange" value="3.4"/>
<param name="maxRange" value="3.6"/>
<remap from="scan" to="/scan_filtered"/>
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter">
<rosparam command="load" file="$(find robot_navigation)/config/lidar_config.yaml"/>
<remap from="base_scan" to="scan"/>
</node> </launch>
obstacle_layer: {enabled: true, lethal_cost_threshold: 100, track_unknown_space: true, unknown_cost_value: -1}
and this is my lidar_scan.yaml
scan_filter_chain:
- name: range
type: laser_filters/LaserScanRangeFilter
params:
use_message_range_limits: false
lower_threshold: 0.2
upper_threshold: 3.5
lower_replacement_value: -.inf
upper_replacement_value: 3.5
dont forget to ramap with
<remap from="scan" to="/scan_filtered"/>
3 | No.3 Revision |
add below parameters to your costmap_common_params.yaml
obstacle_layer: {enabled: true, lethal_cost_threshold: 100, track_unknown_space: true, unknown_cost_value: -1}
okay. my solution is filtering inf
values to maxRange
. this is my gmapping.launch
file.
<launch>
<node pkg="gmapping" type="slam_gmapping" name='gmapping_node' output='log'>
<param name="base_frame" value="base_link"/>
<!--param name="base_frame" value="link_chassis"/-->
<param name="odom_frame" value="odom"/>
<param name="delta" value="0.02"/>
<param name="xmin" value="-25"/>
<param name="ymin" value="-25"/>
<param name="xmax" value="25"/>
<param name="ymax" value="25"/>
<param name="map_update_interval" value="1"/>
<param name="linearUpdate" value="0.05"/>
<param name="angularUpdate" value="0.05"/>
<param name="temporalUpdate" value="0.1"/>
<param name="particles" value="50"/>
<param name="maxUrange" value="3.4"/>
<param name="maxRange" value="3.6"/>
<remap from="scan" to="/scan_filtered"/>
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter">
<rosparam command="load" file="$(find robot_navigation)/config/lidar_config.yaml"/>
<remap from="base_scan" to="scan"/>
</node>
</launch>
and this is my lidar_config.yaml
file:
scan_filter_chain:
- name: range
type: laser_filters/LaserScanRangeFilter
params:
use_message_range_limits: false
lower_threshold: 0.2
upper_threshold: 3.5
lower_replacement_value: -.inf
upper_replacement_value: 3.5
it works for marking free spaces to map. dont forget to filter your laser sacan with laser_filters
pkg.
4 | No.4 Revision |
add below parameters to your costmap_common_params.yaml
obstacle_layer: {enabled: true, lethal_cost_threshold: 100, track_unknown_space: true, unknown_cost_value: -1}
okay. my solution is filtering inf
values to maxRange
. this is my gmapping.launch
file.
<launch>
<node pkg="gmapping" type="slam_gmapping" name='gmapping_node' output='log'>
<param name="base_frame" value="base_link"/>
<!--param name="base_frame" value="link_chassis"/-->
<param name="odom_frame" value="odom"/>
<param name="delta" value="0.02"/>
<param name="xmin" value="-25"/>
<param name="ymin" value="-25"/>
<param name="xmax" value="25"/>
<param name="ymax" value="25"/>
<param name="map_update_interval" value="1"/>
<param name="linearUpdate" value="0.05"/>
<param name="angularUpdate" value="0.05"/>
<param name="temporalUpdate" value="0.1"/>
<param name="particles" value="50"/>
<param name="maxUrange" value="3.4"/>
<param name="maxRange" value="3.6"/>
<remap from="scan" to="/scan_filtered"/>
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter">
<rosparam command="load" file="$(find robot_navigation)/config/lidar_config.yaml"/>
<remap from="base_scan" to="scan"/>
</node>
</launch>
and this is my lidar_config.yaml
file:
scan_filter_chain:
- name: range
type: laser_filters/LaserScanRangeFilter
params:
use_message_range_limits: false
lower_threshold: 0.2
upper_threshold: 3.5
lower_replacement_value: -.inf
upper_replacement_value: 3.5
it works for marking free spaces to map. dont forget to filter your laser sacan with laser_filters
pkg.