Hi,
I'm hoping for some advice. I've tried to create my own launch file based on the hector-rtabmap demo file. But I don't seem to be able to get the sensors working. Once back in my office on Monday I can upload my efforts for further scrutiny, but in the mean time I've a few questions. • Can a single launch file be made that starts up the zed wrapper, rtabmap, hector and urg node rather having to do each individually in separate terminals? • The hector-rtab demo launch it is based around the kinect. What changes need to be made for this to work with the zed camera? • I'm needing to use the mentioned programmes and sensors for handheld mapping. Could you advise what changes would need to be made to to the launch file to achieve this. • Also has anyone had any experience using cartographer with rtabmap for live mapping as the only info I can find is for using rosbags. Many thanks Dan |
Administrator
|
Hi Dan,
1) Yes, you can include other launch files in a launch file, see this page: <launch> <include file="$(find rtabmap_ros)/launch/rtabmap.launch"> <arg name="frame_id" value="base_link"/> ... </include> </launch> 2) In the hector example, adjust the rgb, depth and camera_info topics here to your camera topics (remove image_transport lines to use uncompressed topics directly). 3) The example with hector mapping assumes 2D mapping. For hand-held 6DOF mapping with 2D lidar + camera mapping, there is no example. You may describe more what kind of application you want to achieve. 4) Cartographer and rtabmap are not compatible. They are full SLAM approaches. Where did you see both the same time? Note that in general examples with rosbags can be used live, as the rosbag publishes the data received like if we were on the robot. cheers, Mathieu |
This post was updated on .
Hi Mathieu,
Many thanks for your reply. I'll have a good read through the ros wiki page you've added. I think in my own mind i'm over complicating the whole process, especially as i've seen several different layouts for launch files which I can only assume is due to launch file structure flexibility. I may be be wrong but the sequence for my own launch file would be: 1) urg node 2) hector 3) zed wrapper (zed_wrapper zed_no_tf.launch camera_model:=zedm) 4) rtabmap Or should it be ordered differently? I'm looking to map woodlands using both 2D and 3D means via a portable and handheld device i've put together. Currently i am wanting to achieve 2D mapping with the hokuyo sensor and 3D point cloud with the zed camera. I'm also wanting the lidar to increase stereo camera accuracy. Initial testing just using the zed and rtabmap were quite sucessful apart from the 3D panel in rtabmap not working on jetson xavier! I have been reading through the 2D lidar + camera mapping ros pages. I'm assuming to apply this to handheld mapping instead it will just be a case of removing any links to robots within the launch files? After i wrote the cartographer comment a light bulb clicked with regards to the use of rosbags and the fact rtabmap and cartographer would conflict. Another concern is the use of an imu with the lidar within rtabmap. WIll one increase accuracy or is it best to just stick to rtabmaps odometry? As the Zedm has an imu is it possible to link up the lidar to use this odometry through rtabmap or another way and will this be practical? Would it be better for me to use rtabmaps icp or hectors? Regards Dan |
Administrator
|
Hi Dan,
On jetson xavier (or any other jetson with Jetpack >=4 with Ubuntu 18.04), you can use RVIZ with rtabmap_ros/MapCloud plugin to show the 3D map. Your application is 6DoF mapping. You cannot use 2D lidar with rtabmap for 6DoF mapping, only for 3DoF mapping. We can however threat 2D scans like 3D point clouds, and assemble them to create a 3D map with laser scans. However, those 2D scans (in 6DoF configuration) cannot be used in rtabmap to refine odometry or detect loop closures, unless odometry is very accurate and the scans are assembling while rotating the lidar (creating 360deg X 360deg point clouds). 1) Use laser scan to point cloud conversion script from here: http://wiki.ros.org/laser_geometry 2) Use rtabmap_ros point cloud assembler, setting the odom for fixed frame id <node pkg="nodelet" type="nodelet" name="point_cloud_assembler" args="standalone rtabmap_ros/point_cloud_assembler" output="screen"> <remap from="cloud" to="/lidar_scan_converted_to_point_cloud_topic"/> <remap from="assembled_cloud" to="/assembled_cloud"/> <param name="max_clouds" type="int" value="20" /> <!-- set frame rate of the lidar to assemble a cloud each second --> <param name="fixed_frame_id" type="string" value="odom" /> </node>3) For rtabmap node, enable subscribe_scan_cloud and subscribe to assembled cloud: <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" args="-d" output="screen"> ... <param name="subscribe_scan_cloud" type="bool" value="true" /> <remap from="scan_cloud" to="/assembled_cloud"/> </node> cheers, Mathieu |
HI Mathieu,
Many thanks for your reply. Although i am being slightly stumped still getting a launch file working. Having looked through many examples i still only seem to be able to get everything working separately. I think the links show best what i am trying to achieve, as i will only be walking in straight-ish lines through woodland and holding the camera/lidar horizontally facing forward. https://www.youtube.com/watch?v=0CoyNOVr91k https://www.youtube.com/watch?v=F8pdObV_df4&list=PL0E462904E5D35E29 Cheers Dan |
I have butchered the test_velodyne launch file to work from as a basic frame.
<?xml version="1.0"?> <launch> <arg name="zed_namespace" default="zed" /> <arg name="svo_file" default="" /> <!-- <arg name="svo_file" default="path/to/svo/file.svo"> --> <arg name="zed_node_name" default="zed_node" /> <arg name="camera_model" default="zedm" /> <!-- 'zed' or 'zedm' --> <arg name="publish_urdf" default="true" /> <group ns="$(arg zed_namespace)"> <!-- ZED Wrapper Node--> <include file="$(find zed_wrapper)/launch/zed_camera.launch"> <arg name="svo_file" value="$(arg svo_file)" /> <arg name="node_name" value="$(arg zed_node_name)" /> <arg name="camera_model" value="$(arg camera_model)" /> <arg name="publish_urdf" value="$(arg publish_urdf)" /> </include> </group> <param name="pub_map_odom_transform" value="true"/> <param name="map_frame" value="map"/> <param name="base_frame" value="base_link"/> <param name="odom_frame" value="/odom"/> <node pkg="urg_node" type="urg_node" name="urg_node"> <param name="ip_address" value="192.168.0.10"/> </node> <node pkg="tf" type="static_transform_publisher" name="map_2_odom" args="0 0 0 0 0 0 /map /odom 100"/> <node pkg="tf" type="static_transform_publisher" name="odom_2_base_footprint" args="0 0 0 0 0 0 /odom /base_footprint 100"/> <node pkg="tf" type="static_transform_publisher" name="base_footprint_2_base_link" args="0 0 0 0 0 0 /base_footprint /base_link 100"/> <node pkg="tf" type="static_transform_publisher" name="base_link_2_base_stabilized_link" args="0 0 0 0 0 0 /base_link /base_stabilized 100"/> <node pkg="tf" type="static_transform_publisher" name="base_stablized_2_base_frame" args="0 0 0 0 0 0 /base_stabilized /base_frame 100"/> <node pkg="tf" type="static_transform_publisher" name="base_frame_2_laser_link" args="0 0 0 0 0 0 /base_frame /laser 100"/> <node pkg="tf" type="static_transform_publisher" name="base_2_nav_link" args="0 0 0 0 0 0 /base_frame /nav 100"/> <include file="$(find hector_slam_example)/launch/default_mapping.launch"/> <include file="$(find hector_geotiff)/launch/geotiff_mapper.launch"/> <arg name="rviz" default="false" /> <arg name="rtabmapviz" default="true"/> <arg name="use_imu" default="false"/> <!-- Assuming IMU fixed to lidar with /velodyne -> /imu_link TF --> <arg name="imu_topic" default="/imu/data"/> <arg name="scan_20_hz" default="false"/> <!-- If we launch the velodyne with "rpm:=1200" argument --> <arg name="use_sim_time" default="false"/> <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/> <arg name="frame_id" default="base_link"/> <!-- IMU orientation estimation and publish tf accordingly to os1_sensor frame --> <node if="$(arg use_imu)" pkg="rtabmap_ros" type="imu_to_tf" name="imu_to_tf"> <remap from="imu/data" to="$(arg imu_topic)"/> <param name="fixed_frame_id" value="$(arg frame_id)_stabilized"/> <param name="base_frame_id" value="$(arg frame_id)"/> </node> <group ns="rtabmap"> <node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen"> <remap from="scan_cloud" to="/assembled_cloud"/> <!-- param name="frame_id" type="string" value="$(arg frame_id)"/ --> <param name="odom_frame_id" type="string" value="odom"/> <param if="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="25"/> <param unless="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="15"/> <remap if="$(arg use_imu)" from="imu" to="$(arg imu_topic)"/> <param if="$(arg use_imu)" name="guess_frame_id" type="string" value="$(arg frame_id)_stabilized"/> <param if="$(arg use_imu)" name="wait_imu_to_init" type="bool" value="true"/> <!-- ICP parameters --> <param name="Icp/PointToPlane" type="string" value="true"/> <param name="Icp/Iterations" type="string" value="10"/> <param name="Icp/VoxelSize" type="string" value="0.2"/> <param name="Icp/DownsamplingStep" type="string" value="1"/> <!-- cannot be increased with ring-like lidar --> <param name="Icp/Epsilon" type="string" value="0.001"/> <param name="Icp/PointToPlaneK" type="string" value="20"/> <param name="Icp/PointToPlaneRadius" type="string" value="0"/> <param name="Icp/MaxTranslation" type="string" value="2"/> <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/> <param name="Icp/PM" type="string" value="true"/> <param name="Icp/PMOutlierRatio" type="string" value="0.7"/> <param name="Icp/CorrespondenceRatio" type="string" value="0.01"/> <!-- Odom parameters --> <param name="Odom/ScanKeyFrameThr" type="string" value="0.9"/> <param name="Odom/Strategy" type="string" value="0"/> <param name="OdomF2M/ScanSubtractRadius" type="string" value="0.2"/> <param name="OdomF2M/ScanMaxSize" type="string" value="15000"/> </node> <arg name="rtabmap_args" value="--delete_db_on_start" /> <arg name="rgb_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/rgb/image_rect_color" /> <arg name="depth_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/depth/depth_registered" /> <arg name="camera_info_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/rgb/camera_info" /> <arg name="depth_camera_info_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/depth/camera_info" /> <arg name="approx_sync" value="false" /> <arg name="visual_odometry" value="true" /> <arg name="odom_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/odom" /> <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d"> <!-- param name="frame_id" type="string" value="$(arg frame_id)"/ --> <param name="subscribe_depth" type="bool" value="true"/> <param name="subscribe_rgb" type="bool" value="true"/> <param name="subscribe_scan_cloud" type="bool" value="true"/> <param name="approx_sync" type="bool" value="false"/> <remap from="scan_cloud" to="assembled_cloud"/> <!-- RTAB-Map's parameters --> <param name="Rtabmap/DetectionRate" type="string" value="1"/> <param name="RGBD/NeighborLinkRefining" type="string" value="true"/> <param name="RGBD/ProximityBySpace" type="string" value="true"/> <param name="RGBD/ProximityMaxGraphDepth" type="string" value="0"/> <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/> <param name="RGBD/AngularUpdate" type="string" value="0.05"/> <param name="RGBD/LinearUpdate" type="string" value="0.05"/> <param name="Mem/NotLinkedNodesKept" type="string" value="false"/> <param name="Mem/STMSize" type="string" value="30"/> <!-- param name="Mem/LaserScanVoxelSize" type="string" value="0.1"/ --> <!-- param name="Mem/LaserScanNormalK" type="string" value="10"/ --> <!-- param name="Mem/LaserScanRadius" type="string" value="0"/ --> <param name="Reg/Strategy" type="string" value="1"/> <param name="Reg/Force3DoF" type="string" value="true"/> <!-- 2d slam --> <param name="Grid/CellSize" type="string" value="0.1"/> <param name="Grid/RangeMax" type="string" value="20"/> <param name="Grid/ClusterRadius" type="string" value="1"/> <param name="Grid/GroundIsObstacle" type="string" value="true"/> <!-- ICP parameters --> <param name="Icp/VoxelSize" type="string" value="0.2"/> <param name="Icp/PointToPlaneK" type="string" value="20"/> <param name="Icp/PointToPlaneRadius" type="string" value="0"/> <param name="Icp/PointToPlane" type="string" value="true"/> <param name="Icp/Iterations" type="string" value="10"/> <param name="Icp/Epsilon" type="string" value="0.001"/> <param name="Icp/MaxTranslation" type="string" value="3"/> <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/> <param name="Icp/PM" type="string" value="true"/> <param name="Icp/PMOutlierRatio" type="string" value="0.7"/> <param name="Icp/CorrespondenceRatio" type="string" value="0.4"/> </node> <node if="$(arg rtabmapviz)" name="rtabmapviz" pkg="rtabmap_ros" type="rtabmapviz" output="screen"> <!--param name="frame_id" type="string" value="$(arg frame_id)"/ --> <param name="odom_frame_id" type="string" value="/odom"/> <param name="subscribe_odom_info" type="bool" value="true"/> <param name="subscribe_scan_cloud" type="bool" value="true"/> <param name="approx_sync" type="bool" value="false"/> <remap from="scan_cloud" to="/laser_pointcloud"/> </node> <node pkg="nodelet" type="nodelet" name="point_cloud_assembler" args="standalone rtabmap_ros/point_cloud_assembler" output="screen"> <remap from="cloud" to="/lidar_scan_converted_to_point_cloud_topic"/> <remap from="odom" to="odom"/> <param if="$(arg scan_20_hz)" name="max_clouds" type="int" value="20" /> <param unless="$(arg scan_20_hz)" name="max_clouds" type="int" value="10" /> <param name="fixed_frame_id" type="string" value="odom" /> </node> <node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_slam_example)/launch/rviz_cfg.rviz"/> </group> </launch> |
Administrator
|
Hi,
Working with 2d lidar for 6DOF mapping is not supported in RTAB-Map. You need to check if hector outputs a 6DOF poses, if so you could indeed input 2D scan as a 3D point cloud to rtabmap while using zed camera to get also 3D point cloud. Velodyne is a 3D lidar, I don't think you can re-use the velodyne example. Can you get hector working in your environment? Do you have some results? Is the pose 6DOF? cheers, Mathieu |
Hi Mathieu,
My main problem is syncronising the sensors and getting the correct frame id so the maps allow me to move around. I suppose it would be a case of posting on the ROS forum aswell as the problem being only partly associated with rtab. Although below are some pictures of the set up and outputs. The first pics are using separate launches: roslaunch hector_slam_example hector_hokuyo_eth.launch roslaunch zed_wrapper zed_no_tf.launch roslaunch rtabmap_ros rtabmap.launch \ rtabmap_args:="--delete_db_on_start" \ rgb_topic:=/zed/zed_node/rgb/image_rect_color \ depth_topic:=/zed/zed_node/depth/depth_registered \ camera_info_topic:=/zed/zed_node/rgb/camera_info \ frame_id:=base_link \ approx_sync:=false These pictures are of the setup with the lidar eventually being attached to a plate and then the screen which will be carried in hand at roughly the angle as shown in the picture. Here are the images of the output from the above launch file. The last picture shows how the lidar messes up once moved slightly. Regards Dan |
Administrator
|
Hi,
What is the TF tree? Is base_link linking camera and lidar? You should start rtabmap.launch with visual_odometry:=false to use odometry from hector. You may set odom_frame_id parameter of rtabmap node to hector odometry frame. If you are able to use hector odometry as input with zed camera topics to rtabmap and the map is correctly created, the last step will be to feed also lidar to rtabmap like described in my previous posts. cheers, Mathieu |
RQT outputs don't look the best when making alterations. To be honest i'll have to revaluate the whole project and whether its even worth continuing. Even having made the changes youve previously stated, i just cant seem to grasp what is going on and the changes i need to make.
|
Administrator
|
Hi, I was referring to TF tree in my last post:
$ rosrun tf view_frames |
Hi Mathieu,
Having had a tinker with everything here are my tf trees. The problem now is that the laser scan and zed camera seem to interfere with each other making the everything jump around although the occ map seems fine. I'm assuming it has something to do with the zed wrapper. Would have any idea what i may need to ammend? <?xml version="1.0"?> <!-- Copyright (c) 2018, STEREOLABS. All rights reserved. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. --> <launch> <node name="urg_node" pkg="urg_node" type="urg_node" output="screen"> <param name="ip_address" value="192.168.0.10"/> <param name="serial_port" value="/dev/ttyACM0"/> <param name="serial_baud" value="115200"/> <param name="frame_id" value="laser"/> <param name="calibrate_time" value="true"/> <param name="publish_intensity" value="false"/> <param name="publish_multiecho" value="false"/> <param name="angle_min" value="-1.5707963"/> <param name="angle_max" value="1.5707963"/> </node> <param name="pub_map_odom_transform" value="true"/> <param name="map_frame" value="map"/> <param name="base_frame" value="base_link"/> <param name="odom_frame" value="odom"/> <node pkg="tf" type="static_transform_publisher" name="map_2_odom" args="0 0 0 0 0 0 /map /odom 100"/> <node pkg="tf" type="static_transform_publisher" name="odom_2_scanmatcher_frame" args="0 0 0 0 0 0 /odom /scanmatcher_frame 100"/> <node pkg="tf" type="static_transform_publisher" name="scanmatcher_frame_2_base_link" args="0 0 0 0 0 0 /scanmatcher_frame /base_link 100"/> <node pkg="tf" type="static_transform_publisher" name="base_link_2_laser" args="0 0 -0.01 0 0 0 /base_link /laser 100"/> <include file="$(find hector_slam_example)/launch/default_mapping.launch"/> <arg name="rviz" default="false" /> <arg name="rtabmapviz" default="true"/> <arg name="use_imu" default="false"/> <!-- Assuming IMU fixed to lidar with /velodyne -> /imu_link TF --> <arg name="imu_topic" default="zed_imu_link"/> <arg name="scan_20_hz" default="false"/> <!-- If we launch the velodyne with "rpm:=1200" argument --> <arg name="use_sim_time" default="false"/> <param if="$(arg use_sim_time)" name="use_sim_time" value="false"/> <arg name="frame_id" default="base_link"/> <arg name="nodelet_manager_name" default="zed_nodelet_manager" /> <arg name="zed_namespace" default="zed" /> <arg name="svo_file" default="" /> <!-- <arg name="svo_file" default="path/to/svo/file.svo"> --> <arg name="zed_node_name" default="zed_node" /> <arg name="camera_model" default="zedm" /> <!-- 'zed' or 'zedm' --> <arg name="publish_urdf" default="true" /> <!-- Nodelet Manager --> <node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" /> <group ns="$(arg zed_namespace)"> <!-- ZED Wrapper Node--> <include file="$(find zed_wrapper)/launch/zed_camera.launch"> <!-- include file="$(find zed_wrapper)/launch/zedm.launch" --> <!-- include file="$(find zed_wrapper)/launch/zed_no_tf.launch" --> <!-- include file="$(find zed_ros_wrapper)/launch/zed_nodelet_laserscan.launch" --> <arg name="svo_file" value="$(arg svo_file)" /> <arg name="node_name" value="$(arg zed_node_name)" /> <arg name="camera_model" value="$(arg camera_model)" /> <arg name="publish_urdf" value="$(arg publish_urdf)" /> </include> <!-- Virtual laser scan as nodelet --> <!-- "$ sudo apt install ros-melodtic-depthimage-to-laserscan" --> <node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan" args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet zed_nodelet_manager"> <param name="scan_height" value="10"/> <param name="output_frame_id" value="zed_left_camera_frame"/> <param name="range_min" value="0.45"/> <remap from="image" to="$(arg zed_node_name)/depth/depth_registered"/> </node> </group> <!-- RTAB-map Node--> <node pkg="nodelet" type="nodelet" name="point_cloud_assembler" args="standalone rtabmap_ros/point_cloud_assembler" output="screen"> <remap from="cloud" to="/lidar_scan_converted_to_point_cloud_topic"/> <remap from="assembled_cloud" to="/assembled_cloud"/> <param name="max_clouds" type="int" value="20" /> <!-- set frame rate of the lidar to assemble a cloud each second --> <param name="fixed_frame_id" type="string" value="odom" /> </node> <include file="$(find rtabmap_ros)/launch/rtabmap.launch"> <arg name="rtabmap_args" value="--delete_db_on_start" /> <arg name="rgb_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/rgb/image_rect_color" /> <arg name="depth_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/depth/depth_registered" /> <arg name="camera_info_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/rgb/camera_info" /> <arg name="depth_camera_info_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/depth/camera_info" /> <arg name="frame_id" value="base_link" /> <arg name="approx_sync" value="false" /> <arg name="visual_odometry" value="false" /> <arg name="odom_topic" value="/$(arg zed_namespace)/$(arg zed_node_name)/odom" /> <arg name="rviz" value="true" /> <!-- RTAB-Map's parameters --> <param name="Rtabmap/DetectionRate" type="string" value="1"/> <param name="RGBD/NeighborLinkRefining" type="string" value="true"/> <param name="RGBD/ProximityBySpace" type="string" value="true"/> <param name="RGBD/ProximityMaxGraphDepth" type="string" value="0"/> <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/> <param name="RGBD/AngularUpdate" type="string" value="0.05"/> <param name="RGBD/LinearUpdate" type="string" value="0.05"/> <param name="Mem/NotLinkedNodesKept" type="string" value="false"/> <param name="Mem/STMSize" type="string" value="30"/> <!-- param name="Mem/LaserScanVoxelSize" type="string" value="0.1"/ --> <!-- param name="Mem/LaserScanNormalK" type="string" value="10"/ --> <!-- param name="Mem/LaserScanRadius" type="string" value="0"/ --> <param name="Reg/Strategy" type="string" value="1"/> <param name="Reg/Force3DoF" type="string" value="true"/> <!-- 2d slam --> <param name="Grid/CellSize" type="string" value="0.1"/> <param name="Grid/RangeMax" type="string" value="20"/> <param name="Grid/ClusterRadius" type="string" value="1"/> <param name="Grid/GroundIsObstacle" type="string" value="true"/> <param name="Grid/FromDepth" type="string" value="false"/> <!-- ICP parameters --> <param name="Icp/VoxelSize" type="string" value="0.2"/> <param name="Icp/PointToPlaneK" type="string" value="20"/> <param name="Icp/PointToPlaneRadius" type="string" value="0"/> <param name="Icp/PointToPlane" type="string" value="true"/> <param name="Icp/Iterations" type="string" value="10"/> <param name="Icp/Epsilon" type="string" value="0.001"/> <param name="Icp/MaxTranslation" type="string" value="3"/> <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/> <param name="Icp/PM" type="string" value="true"/> <param name="Icp/PMOutlierRatio" type="string" value="0.7"/> <param name="Icp/CorrespondenceRatio" type="string" value="0.4"/> <param name="subscribe_scan_cloud" type="bool" value="true" /> <remap from="scan_cloud" to="/assembled_cloud"/> <!-- Odom parameters --> <param name="Odom/ScanKeyFrameThr" type="string" value="0.9"/> <param name="Odom/Strategy" type="string" value="0"/> <param name="OdomF2M/ScanSubtractRadius" type="string" value="0.2"/> <param name="OdomF2M/ScanMaxSize" type="string" value="15000"/> </include> </launch> Thanks Dan |
Administrator
|
I don't remember, but I think if you don't subscribe to zed's odom topic, the TF from zed node won't be published. In your case (see Tf Tree), you seem to have both hector and zed publishing odometry, one parent of the other. You should use only one. See https://github.com/introlab/rtabmap_ros/blob/master/launch/demo/demo_hector_mapping.launch in details when hector argument is true. Refer to this example: http://wiki.ros.org/rtabmap_ros/Tutorials/SetupOnYourRobot#Kinect_.2B-_2D_laser
Kinect topics would be modified for zed corresponding topics. cheers, Mathieu |
Free forum by Nabble | Edit this page |