0
$\begingroup$

Rosanswers logo

I'm trying to use octomap with a velodyne HDL-32E sensors point cloud. I move around in a large complex (Approx 1 km by 1 km) and generate the map. The map update rate is really good when the total map size is small (I can see moving cars and people being classified into obstacles), but as the map size increases, the update rate slows quite a lot. Can someone suggest me ways to overcome this problem? I'm currently considering just running the map in the local frame to get immediate obstacles, but this will defeat the purpose (global planning) for which I had switched to octomap.


Originally posted by raskolnikov_reborn on ROS Answers with karma: 53 on 2015-12-19

Post score: 3


Original comments

Comment by 2ROS0 on 2015-12-20:
This obstacle detection of people and cars is running separately? Are you sure it is the Octomap update that's the bottleneck?

Comment by raskolnikov_reborn on 2015-12-21:
I meant those as examples to illustrate that moving obstacles are detected nearly instantly at the beginning but not at the end. Static fixtures such as walls and trees etc are detected properly all the way to the end but the updates get slower and slower with the increase in map size.

Comment by raskolnikov_reborn on 2015-12-25:
I can confirm that the problem is related to map size more than time of operation. If is create a local window map without a global frame that is both map and base frame are the sensor, the problem is greatly reduced. With a finite map size, octomap updates do not get slower over time.

Comment by krishnaece1505 on 2016-03-01:
I am trying to use octomap to create a 3D map form point clouds input in Pointcloud2 format. I have built the libraries. But, when I launch the octomap_mapping.launch file, I see no output in RVIZ in /map. Since, you have got it working, may I know the procedure to use this library?

Comment by chukcha2 on 2016-03-02:
I was told that octomap is used to create a map from already registered point clouds (or a set of point clouds and transforms). I haven't found a good way to register point clouds from a velodyne lidar (VLP-16 in my case). Can you please share how you are able to register point clouds?

Comment by raskolnikov_reborn on 2016-04-19:
Just start publishing a transform between your laser frame and your global frame. specify the sensor frame in the launch file and the global frame and you should be done. Make sure you provide the pointcloud in the sensor frame if you enable ground filtering otherwise you get out of range errors.

Comment by chukcha2 on 2016-04-19:
Thanks, but what I am asking is how to get that transform (between laser frame and global frame). What method are you using? Thanks.

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

I would expect that map updates themselves do not slow down over time, as the computation of the voxels to "touch"/modify should take similar average computation time no matter where in the octomap the sensor is placed. Of course, if the average distance of range measurements increases over the course of your datasets, an increase in processing time is to be expected as the raytracing takes longer then. Of course, there are other factors at play that might have adverse effects, like allocation and placement of voxel information in memory.

What definitely takes longer the larger the map grows is iterating over all cells, for instance for visualization purposes. Are you possibly doing that somewhere in your code? If you are using the standard octomap_server , the publishAll() method is called after every map update. This method iterates over all cells, so it would explain a slow-down with increasing map size nicely.


Originally posted by Stefan Kohlbrecher with karma: 24361 on 2016-04-20

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by raskolnikov_reborn on 2016-04-20:
Thanks. That may be it. I sort of worked around the issue by only using a local map to navigate obstacles and clearing everything outside a bounding box every second. But Maybe If I could just get the map server to publish changes in cell state rather than all the cells, it'll be faster.

Comment by raskolnikov_reborn on 2016-04-22:
Hi. In line with my earlier comment. Is there a way I can configure octomap_server to not publish/iterate the entire map again and only publish the updates.

Comment by Stefan Kohlbrecher on 2016-04-22:
I don't think so, but you could easily fork it and then do whatever you want. Alternatively, you could use the octomap library in your own node and this way have full control over what happens.

$\endgroup$
0
$\begingroup$

Rosanswers logo

I get the GPS/INS position in lat, long, alt, roll, pitch, yaw. Compute the utm odometry using the gps_common package. so I now have the value in meters (x,y,z,roll,pitch,yaw). Then publish a transform using this position. Look at the code below for reference

    void poseCallback(const gps_common::GPSFixConstPtr& msg){


  static tf::TransformBroadcaster br;
  tf::Transform transform;
  double x,y;
  std::string zone;
  gps_common::LLtoUTM(msg->latitude, msg->longitude, northing, easting, zone);
 
  transform.setOrigin(tf::Vector3( (easting), (northing),  0.0));
  tf::Quaternion q;
  q.setRPY(msg->roll ,msg->pitch, msg->track );
  transform.setRotation(q);
  br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", "vehicle"));

  publish_map_tf(msg);
}

I also publish a static transform between the vehicle and the velodyne frame which is the x,y,z translation and r,p,y rotation between the co-ordinate frame of the GPS/INS and the Laser Sensor. Hope that helps


Originally posted by raskolnikov_reborn with karma: 53 on 2016-04-20

This answer was NOT ACCEPTED on the original site

Post score: 1

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.