ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Autoware NDT_Matching not matching

asked 2019-07-11 18:27:27 -0500

bcopenha gravatar image

Hello,

I am currently attempting to run Autoware’s ndt_matching process with little success. I have gotten the ndt_matching to work in the ROSBAG Demo provided on the gitlab with the suggested/preset settings and with changing it from starting with GNSS to starting at an initial position of [0,0,0,0,0,0] and changing the type of matching (pcl_generic, pcl_anh, and pcl_openmp).

So far I have built a few .pcd map files with the ndt_mapping process and have attempted to use that to localize off of using a similar process to what is described in the example launch files:

  • my_mapping.launch with tf_launch (with the world to map transform set to 0,0,0 instead of the default values in the usual tf.launch) and the points_map_loader node with the .pcd file I created previously.
  • my_sensing.launch with a driver for a 64-plane Ouster LiDAR that outputs a topic /os1_cloud_node/points in PointCloud2 format and a driver for a Microstrain IMU that outputs /gps/fix and translates that into the /fix topic required by ndt_matching (of msg type NavSatFix)
  • my_localization.launch:

    • setup_tf.launch of base_link to os1_lidar
    • vehicle_model.launch that loads the urdf file for my vehicle and starts the joint_state_publisher and robot_state_publisher nodes
    • points_downsample.launch where it looks at the /os1_cloud_node/points topic (remaped from the /points_raw topic) for point values and I have tried multiple values for the voxel_grid_filter
    • fix2tfpose.launch

    I then go in manually to add the ndt_matching from the Runtime Manager (and have started also using ndt_matching_monitor from there as well).

Since the ndt_mapping process does not seem to include gnss data from the bag file, I initialize the position with [0,0,0,0,0,0]. Predict Pose is ON. I have increased and decreased the following values individually and in combination: Error Threshold, Resolution, Step Size, Transformation Epsilon, and Maximum Iterations for three of the four Method Types (pcl_generic, pcl_anh, and pcl_openmp) {did not use the pcl_anh_gpu due to memory errors on my computer related to the gpu} I am not using Odometry nor IMU but I do have Get Height checked because that was what the original ndt_matching had as its option on the original my_localization.launch. I have started with the preset settings (the ones that are used and work on the ROSBAG demo) of Error Threshold=1, Resolution=1, Step Size=0.1, Transformation Epsilon=0.01, and Maximum Iterations=30, but again have increased/decreased those values and tested the results.

I have created 3 .pcd maps: two of the area surrounding my building, with a different [0,0,0] for both, and one inside my lab. Initially, when using the outside maps, I was having the problem (mostly with pcl_openmp) of the ndt_matching initially checking around the start point but then eventually zooming off the map unable to recover. However, now even when I run the map inside my lab and the vehicle has not moved from the position where the map was recorded, the ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2019-07-12 00:34:27 -0500

Yamato Ando gravatar image

Please try as follows.

  1. Play rosbag(slam_topics_2019-07-01-10-02-59.bag) and pause immediately.

  2. Execute the following command to fix header.stamp to current ros time.

    $ rosrun topic_tools relay_field /os1_cloud_node/points /points_raw sensor_msgs/PointCloud2 "header:  
     seq: m.header.seq  
     stamp: now  
     frame_id: m.header.frame_id  
     height: m.height  
    width: m.width  
    fields:  
    - {name: "x", offset: 0, datatype: 7, count: 1}  
    - {name: "y", offset: 4, datatype: 7, count: 1}  
    - {name: "z", offset: 8, datatype: 7, count: 1}  
    - {name: "intensity", offset: 16, datatype: 7, count: 1}  
    - {name: "t", offset: 20, datatype: 6, count: 1}  
    - {name: "reflectivity", offset: 24, datatype: 4, count: 1}  
    - {name: "ring", offset: 26, datatype: 2, count: 1}  
    - {name: "noise", offset: 28, datatype: 4, count: 1}  
    - {name: "range", offset: 32, datatype: 6, count: 1}  
    is_bigendian: m.is_bigendian  
    point_step: m.point_step  
    row_step: m.row_step  
    data: m.data  
    is_dense: m.is_dense"
    
  3. Set BaseLink to Localizer(params is [0.465, 0, 1.945, 3.142, 0, 0])

  4. Publish Point Cloud Map(autoware-190703-2.pcd)

  5. Publish TF(autoware/ros/src/.config/tf/tf_local.launch)

  6. Launch voxel_grid_filter(config: "Points Topic" is "/points_raw")

  7. Launch ndt_matching(config: "Initial Pos" is [-5.68, 59.18, -5.775, -0.141, 0.004, 0.703])

  8. Restart rosbag.

edit flag offensive delete link more

Comments

Yamato,

Thank you for your reply!

The above works, with a slight modification: Step 2 should not have the indent before height: m.height and I also put the entire part in green into single quotes ( ' ) instead of double as to not interfere with the naming of the fields.

My follow-up question is how did you get the values for the Initial Pos for Step 7? This seems to have been the source of my issue and I am wondering what determined them. Thank you again!

bcopenha gravatar image bcopenha  ( 2019-07-12 16:24:22 -0500 )edit
1

Thank you for your comment on the correction. The method of determining the value of Initial Pos used the 2D Pose Estimate of Rviz and searched the position which can be matched manually. And the output value of the following command was made Initial Pose.

$ rosrun tf tf_echo world base_link

Yamato Ando gravatar image Yamato Ando  ( 2019-07-15 20:53:38 -0500 )edit

@Yamato

Hello,

I have been tested Autoware localization (lidar localizer using ndt_matching) with Velodyne (16, 32 and 64) model sensors and Ouster 64 channel sensor. With all the sensor localizer working good. But with the Hesai Pandar64 channel lidar getting an error like this bellow. Above mentioned sensors tested with the same map data and with the frame id modified to "velodyne".

Could you please comment on this, looking forward to hearing from you.

Ajay gravatar image Ajay  ( 2019-09-20 03:02:41 -0500 )edit

@Ajay Hello, Please paste the error message.

Yamato Ando gravatar image Yamato Ando  ( 2019-09-26 20:27:47 -0500 )edit

@Ajay Since this is an unrelated and new issue, please post a new question.

Josh Whitley gravatar image Josh Whitley  ( 2019-09-27 07:55:36 -0500 )edit

@Yamato Thanks for your kind reply.

Error Message : For frame [velodyne]: No transform to fixed frame [world]. TF error: [Lookup would require extrapolation into the past. Requested time 946655660.000381000 but the earliest data is at time 1568785504.549147331, when looking up transform from frame [velodyne] to frame [world]]

Also commented in the Autoware forum https://github.com/autowarefoundation/autoware/issues/2321

Ajay gravatar image Ajay  ( 2019-09-28 02:54:05 -0500 )edit

@Ajay It seems that TF has not been converted well, because the sensor time stamp is strange. Please modify the sensor driver.

Yamato Ando gravatar image Yamato Ando  ( 2019-09-30 02:47:02 -0500 )edit

@Yamato Thanks for your reply, I will check the sensor driver and get back to you.

Ajay gravatar image Ajay  ( 2019-09-30 19:51:42 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-07-11 18:27:27 -0500

Seen: 2,062 times

Last updated: Sep 20 '19