Closed kamakshijain closed 1 year ago
Apologies for being late in response. I will have a working cycles ~at the end of this week to check and try reproduce the problem on my side, and then I will tell an updates on this.
I've experimented locally the situation, and I see ClearEntireCostmap
service is working as expected in Nav2: for global costmap all artifacts are being removed in whole costmap, for local costmap I did not find any clue to remain artifacts on it (everything is being cleared on costmap update cycle).
Please note, that ClearEntireCostmap
service is not disabling costmap at all. It is forcing costamp to reset, clearing all unnecessary artifacts on it.
@kamakshijain, from your illustrations it looks like for global costmap is also works fine. Initially made noise at the costmap is being removed from it after ClearEntireCostmap
service call:
Remaining items, which could be recognised as "noise" - is a localization error. Since global costmap is being consisted from static and obstacle layers, they both generating the data on costmap that have being merged on it. Static layer operates in the map
frame, and put the input map on the costmap. Obstacle layer operates in the odom
frame, and adds on the master costmap sensors data. If robot is being localized incorrectly, the data will be looking noisy, but it is still expected correct behavior in this case:
As for local costamp illustrations, from pictures it looks like you have referencing on the global costmap on the pictures instead. All the data on local costamp is also seems to being reset.
If you want to completely disable costmap you need to set <layer_name>.enabled
parameter to False
. Like ROS1, it is still available in Nav2: it is being dynamically supported. It could be something like the following command for the global_costmap:
ros2 service call /global_costmap/global_costmap/set_parameters rcl_interfaces/srv/SetParameters "{parameters: [{name: "static_layer.enabled", value: {type: 1, bool_value: False}}, {name: "obstacle_layer.enabled", value: {type: 1, bool_value: False}}, {name: "inflation_layer.enabled", value: {type: 1, bool_value: False}}]}"
And set all these layers to True
if you want to bring them back again. I think, this is what you are looking for.
Hello, Project Statement: Robot will be interacting with an object (physically touching the object) present in the environment after T + 10 mins (example). Basically, the object at start time is part of the world and thus considered as an obstacle by costmap. After T + 10 mins when I want to interact with the object, I don't want it to be considered as an obstacle.
Trying to Use Plugin:
ClearEntireCostmap plugin (and similar costmap manipulation plugins) for both globalcostmap and localcostmap. Follow up on #3243 in humble.
I was able to verify what Steve Macenski tested on rolling. I was able to clear the costmap for old scatter generated by wrong initialization, however I was not able to clear costmap for scatter generated for current position [for global costmap only]. Question 1: is it suppose to clear/disable costmap for current time? In ROS1: setting the costmap enable parameter to false, completely disabled costmap, I am looking for that kind of feature.
WANTING: to Disable costmap at run-time, can I do that using this or some other service?
Issue2: I was not able to see any difference when I used service call ClearEntireCostmap for local costmap. There was no difference between before and after.
Please see the attached picture. Picture contains, navigation logs, cmd line service call to global and local costmap and rviz.
ros2 service call /global_costmap/clear_entirely_global_costmap nav2_msgs/srv/ClearEntireCostmap "{request: {}}"
orros2 service call /local_costmap/clear_entirely_local_costmap nav2_msgs/srv/ClearEntireCostmap "{request: {}}"
Required Info:
Operating System:
ROS2 Version:
Version or commit hash:
DDS implementation:
Steps to reproduce issue
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
echo $RMW_IMPLEMENTATION
ros2 service call /global_costmap/clear_entirely_global_costmap nav2_msgs/srv/ClearEntireCostmap "{request: {}}"
Expected behavior
Global Costmap: Before: After:
Actual behavior
Global Costmap Before: After:
Issue 2:
Local Costmap no change
Additional information
Added nav2_config
Feature request
Disable Global and Local Costmap at Run-Time.
Feature description
ROS1 was able to set enable parameter to false and the costmap would get disabled at run-time. expecting something similar to be able to interact with objects in the environment.
Implementation considerations