Jack, On Mon, Sep 20, 2010 at 7:45 PM, Jack O'Quin wrote: > It may seem nonsensical to ask about the "height" of a 2D costmap, but > I am confused by what we saw today and could use some help making > sense of it and deciding what to do. > > As mentioned in an earlier message, I am experimenting with > costmap_2d_node to see if our autonomous vehicle can use it for sensor > fusion. It seems to work OK in stage simulation. We are running ROS > C-turtle on Ubuntu Karmic and Lucid. > > Today, we experimented with it on the actual car feeding it an > obstacle point cloud from our Velodyne 3D LIDAR. I can view the > PointCloud in rviz and it looks reasonable. But, when I view the > obstacle GridCells, none appear. However, rviz can display the unknown > GridCells (which is all of them). Strangely, they appear a couple of > hundred meters below the car and the obstacles. This offset looks > close to the actual elevation of our test area (209 meters above sea > level), so I am guessing the map may think it's at elevation z=0. > This seems like a reasonable assumption. The navigation stack just publishes those markers in the global_frame of the costmap and let's rviz display them wherever, so this implies that, perhaps, your map frame is not correct in Z. Have you tried using rviz to look at tf itself? You should see the map and odometric frames where you expect them. > > Our GPS odometry source publishes the actual elevation for the > nav_msgs/Odometry message and /odom->/vehicle transform. There is > (currently) a static identity transform from /map to /odom (0,0,0 > translation and 0,0,0,1 rotation quaternion). So, I expected the map > to appear at the same elevation as the vehicle and the odometry. I > can't be certain whether this is purely an rviz display issue or > inherent to the costmap, but I suspect the latter, because it would > explain why no obstacles appear in the map, they are all way above the > /costmap/max_obstacle_height parameter setting (2.7m). I did try > adding 209 to the max and min obstacle heights to see if that would > make a difference, and it did not. > Looking at the frames should help here I'd think. Adding 209 to the max and min obstacle heights might not be enough if you're using the voxel grid underlying model for the costmap. I'd also expect you to have to set the origin_z parameter on the voxel grid: http://www.ros.org/wiki/costmap_2d#Map_type_parameters. The correct way to solve this, however, is probably to make sure that the global_frame of the costmap exists at the correct height to begin with. > > Another possible explanation is that the velodyne points are published > as "/velodyne/obstacles". I can't tell whether costmap_2d allows a > containing slash or not. Is it legal to set the > /costmap/observation_sources parameter to "velodyne/obstacles" and > then define parameters with names like > "/costmap/velodyne/obstacles/sensor_frame"? > Any ideas what is going on and suggestions for what to do about it? > As I mentioned in my response to your previous e-mail, I think this could work, but I'd suggest removing the slash from the sensor_name and instead setting the topic parameter to "/velodyne/obstacles." Actually, come to think of it. If you have the leading "/"... I'm not sure things would work as the sensor might look for its parameters in the /velodyne/obstacles namespace instead of the /costmap/velodyne/obstacles namespace. Using a sensor name without a "/" to be safe seems like a good idea. Hope this helps, Eitan -- > joq > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users >