1 Star 0 Fork 0

焦建军/dynamic_robot_localization

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
克隆/下载
octo_map.launch 3.49 KB
一键复制 编辑 原始数据 按行查看 历史
Carlos Costa 提交于 2015-07-31 00:32 +08:00 . Improved parameterization of drl launch file.
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="octomap_file" default="" />
<arg name="map_frame_id" default="map" />
<arg name="map_out_topic" default="/map" />
<arg name="cloud_out_topic" default="reference_pointcloud_update" />
<arg name="base_frame_id" default="base_footprint" />
<arg name="sensor_frame_id" default="laser" />
<arg name="override_sensor_z" default="false" />
<arg name="override_sensor_z_value" default="0.0" />
<arg name="cloud_in" default="aligned_pointcloud_outliers" /> <!-- ambient_pointcloud | aligned_pointcloud | aligned_pointcloud_outliers | aligned_pointcloud_inliers -->
<arg name="occupancy_grid_in" default="initial_2d_map" />
<arg name="resolution" default="0.025" />
<arg name="minimum_amount_of_time_between_ros_msg_publishing" default="5.0" />
<arg name="minimum_number_of_integrations_before_ros_msg_publishing" default="10" />
<arg name="nodes_respawn" default="true" />
<node pkg="octomap_server" type="octomap_server_node" name="$(anon octomap_server)" args="$(arg octomap_file)" output="screen" respawn="$(arg nodes_respawn)" clear_params="true" >
<param name="frame_id" type="str" value="$(arg map_frame_id)" />
<param name="resolution" type="double" value="$(arg resolution)" />
<param name="base_frame_id" type="str" value="$(arg base_frame_id" />
<param name="sensor_frame_id" type="str" value="$(arg sensor_frame_id)" />
<param name="override_sensor_z" type="bool" value="$(arg override_sensor_z)" />
<param name="override_sensor_z_value" type="double" value="$(arg override_sensor_z_value)" />
<param name="height_map" type="bool" value="true" />
<param name="sensor_model/max_range" type="double" value="200" />
<param name="sensor_model/hit" type="double" value="0.6" />
<param name="sensor_model/miss" type="double" value="0.45" /> <!-- 0.5 for static environments (will not decrease the occupied probability when ray tracing) -->
<param name="sensor_model/min" type="double" value="0.07" />
<param name="sensor_model/max" type="double" value="0.99" />
<param name="sensor_model/occupancy_treshold" type="double" value="0.7" />
<param name="latch" type="bool" value="true" />
<param name="filter_ground" type="bool" value="false" />
<param name="filter_speckles" type="bool" value="true" />
<param name="ground_filter/distance" type="double" value="0.02" />
<param name="ground_filter/angle" type="double" value="0.15" />
<param name="ground_filter/plane_distance" type="double" value="0.05" />
<param name="pointcloud_min_z" type="double" value="-1.0" />
<param name="pointcloud_max_z" type="double" value="2.5" />
<param name="occupancy_min_z" type="double" value="-1.0" />
<param name="occupancy_max_z" type="double" value="2.5" />
<param name="occupancy_grid_2d_min_z" type="double" value="-1.0" />
<param name="occupancy_grid_2d_max_z" type="double" value="2.5" />
<param name="occupancy_grid_2d_initialized_as_free" type="bool" value="false" />
<param name="occupancy_grid_in" type="str" value="$(arg occupancy_grid_in)" />
<param name="minimum_amount_of_time_between_ros_msg_publishing" type="double" value="$(arg minimum_amount_of_time_between_ros_msg_publishing)" />
<param name="minimum_number_of_integrations_before_ros_msg_publishing" type="double" value="$(arg minimum_number_of_integrations_before_ros_msg_publishing)" />
<remap from="cloud_in" to="$(arg cloud_in)" />
<remap from="projected_map" to="$(arg map_out_topic)" />
<remap from="octomap_point_cloud_centers" to="$(arg cloud_out_topic)" />
</node>
</launch>
Loading...
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/jiaojianjun-com/dynamic_robot_localization.git
git@gitee.com:jiaojianjun-com/dynamic_robot_localization.git
jiaojianjun-com
dynamic_robot_localization
dynamic_robot_localization
hydro-devel

搜索帮助