Closed jaredjohansen closed 5 years ago
gmapping thresholds the occupancy grid values into three distinct values: occupied, free, and busy. Cartographer's occupancy grid node publishes a range of values for each cell depending on certainty. Perhaps the costmap planner expects the map format to be like gmapping's. Try hacking the code that the occupancy grid node uses to calculate the values in the map message here to perform thresholding.
Thanks, @ojura! Playing with that line has taught me that my global costmap expects that value to be 100 before it will register as a lethal obstacle.
I can add in a tiny hack (with a custom threshold) so that obstacles show up on my global costmap a lot sooner:
int value =
observed == 0
? -1
: ::cartographer::common::RoundToInt((1. - color / 255.) * 100.);
if (value > 65) {
value = 100;
}
It has one side effect. Because my input is a pointcloud, the lowest rings hit the ground plane and cartographer marks those as obstacles just as quickly. Is there a way to have cartographer ignore any pointcloud points below a certain z distance?
Thanks again!
Found the answer. In my config file, I added these lines:
TRAJECTORY_BUILDER_2D.min_z = -0.1
TRAJECTORY_BUILDER_2D.max_z = 1.5
I'm satisfied with this workaround and am closing the issue. Thanks, @ojura for your help in identifying the place in the code for the workaround .
@jaredjohansen I would like to share another hack which I think results in better looking costmaps. Instead of the hack above, change DrawTexture
in cartographer/io/submap_painter.cc
:
uint8_t alpha_value = alpha.at(i);
if (intensity_value == 0 && alpha_value > 0) {
alpha_value = 255;
}
This way, we make darker only the cells which are actually occupied, and not grayish-looking cells in the final map which are actually free, but just really uncertain so they ended up looking dark after blending.
Thanks, @ojura, for another helpful way to do this.
With the original hack, I've been able to get my downstream nodes to work satisfactorily. When I revisit the costmaps, I will look into this approach.
thanks, @ojura, this helped me a lot.
Changing the min and max z would be unsuitable for me, as i use an VLP16 on my robot.
If I get the "TRAJECTORY_BUILDER_2D.min_z" below a certain threshold, cartographer start's to get part of the ground as an obstacle.
With this modification I was able to let this configuration and still get a good costmap for navigation.
Hello, everyone,
@bfMendonca I have a similar problem with my VLP-16 recognizing the ground as an obstacle. Due to the construction my robot has a fluctuation around the pitch axis.
@ojura which parameter and where exactly do I have to make your described setting?
Is there a possibility to inform the cartographer about these variations or do I have to use 3D Trajectory?
Thank you
@jaredjohansen I would like to share another hack which I think results in better looking costmaps. Instead of the hack above, change
DrawTexture
incartographer/io/submap_painter.cc
:uint8_t alpha_value = alpha.at(i); if (intensity_value == 0 && alpha_value > 0) { alpha_value = 255; }
This way, we make darker only the cells which are actually occupied, and not grayish-looking cells in the final map which are actually free, but just really uncertain so they ended up looking dark after blending.
hi, is this a node? how should i do with this file? running it with cartographer node? because my cartographer file doesnot have this file.
I am running cartographer and getting a very nice map. I’m quite pleased with this package, the maps it produces, and a few other bells and whistles. Thanks!
I am running into two issues involving cartographer and my global costmap:
A few other notes:
I have put the following files at this link:
Last thing: when I use gmapping, my global costmap works fine. Since gmapping works fine, and since my global costmap is produced from /map (which is published by cartographer_occupancy_grid_node), I suspect there is something unique about the map that cartographer produces that is causing the global costmap to not work.