Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dev/heap example #74

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
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
39 changes: 39 additions & 0 deletions ros/open3d_slam_ros/launch/examples/rsl_heap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<?xml version="1.0" encoding="UTF-8"?>

<launch>

<arg name="launch_prefix" default="" doc="gdb -ex run --args"/>
<arg name="launch_rviz" default="false" />
<arg name="cloud_topic" default="/ouster_points_self_filtered" />
<arg name="parameter_filename" default="param_ouster_os0_128.lua"/>
<arg name="parameter_folder_path" default="$(find open3d_slam_ros)/param/"/>
<arg name="map_saving_folder" default="$(find open3d_slam_ros)/data/maps/"/>
<arg name="num_accumulated_range_data" default="1"/>
<arg name="is_read_from_rosbag" default="false"/>
<arg name="rosbag_filepath" default=""/>
<arg name="use_sim_time" default="false"/>


<!-- END OF ARGS -->

<param name="/use_sim_time" value="$(arg use_sim_time)" />

<node name="mapping_node" pkg="open3d_slam_ros"
type="mapping_node" output="screen" launch-prefix="$(arg launch_prefix)">

<param name="cloud_topic" type="string" value="$(arg cloud_topic)" />
<param name="parameter_folder_path" type="string" value="$(arg parameter_folder_path)" />
<param name="parameter_filename" type="string" value="$(arg parameter_filename)" />
<param name="num_accumulated_range_data" value="$(arg num_accumulated_range_data)"/>
<param name="is_read_from_rosbag" value="$(arg is_read_from_rosbag)"/>
<param name="rosbag_filepath" value="$(arg rosbag_filepath)"/>
<param name="map_saving_folder" value="$(arg map_saving_folder)"/>
</node>


<include
file="$(find open3d_slam_ros)/launch/vis.launch"
if="$(arg launch_rviz)">
</include>

</launch>
2 changes: 2 additions & 0 deletions ros/open3d_slam_ros/param/param_ouster_os0_128.lua
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,10 @@ params = deepcopy(DEFAULT_PARAMETERS)
--ODOMETRY
params.odometry.scan_processing.voxel_size = 0.15
params.odometry.scan_processing.downsampling_ratio = 0.5
params.odometry.is_publish_odometry_msgs = true

--MAPPER_LOCALIZER
params.mapper_localizer.is_attempt_loop_closures = false
params.mapper_localizer.is_merge_scans_into_map = false
params.mapper_localizer.is_build_dense_map = false
params.mapper_localizer.is_use_map_initialization = false
Expand Down