Commit 2b927de1 authored by Julia Sanchez's avatar Julia Sanchez
Browse files

[tmp] Specific to rosbag received

* see /Vision/Data/kitti_velodyne
parent 788d405f
......@@ -60,6 +60,7 @@
<node name="velodyne_conversion" pkg="lidar_conversions" type="velodyne_conversion_node" output="screen">
<param name="rpm" value="$(arg rpm)"/>
<param name="timestamp_first_packet" value="$(arg timestamp_first_packet)"/>
<remap from="velodyne_points" to="/ct_icp/pointcloud"/>
</node>
<!-- LiDAR SLAM : compute TF slam_init -> velodyne -->
......@@ -75,8 +76,4 @@
<include file="$(find lidar_slam)/launch/gps_conversions.launch"/>
</group>
<!-- Moving base coordinates systems description tf_FROM_to_TO X Y Z rZ rY rX FROM TO -->
<node pkg="tf2_ros" type="static_transform_publisher" name="tf_base_to_lidar" args="0 0 0 0 0 0 base_link velodyne"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="tf_base_to_gps" args="0 0 0 0 0 0 base_link gps"/>
</launch>
\ No newline at end of file
......@@ -4,7 +4,7 @@
# SLAM will compute the pose of tracking_frame in odometry_frame coordinates system, using measurements in input pointcloud frames.
odometry_frame: "odom" # Frame in which SLAM odometry and maps are expressed (default: odom)
tracking_frame: "base_link" # Frame to track (ensure a valid TF tree is published to link input pointcloud frame_id) (default: base_link)
tracking_frame: "/base_link" # Frame to track (ensure a valid TF tree is published to link input pointcloud frame_id) (default: base_link)
# Input LiDAR frames topics, expected as sensor_msgs/PointCloud2 messages with the following fields:
# - x, y, z (float): point coordinates
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment