diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index f2ee41e..a7d52dd 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -320,7 +320,7 @@ local_costmap: inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 2.0 # was 3.0 ;exponential rate at which the obstacle cost drops off (default: 10) - inflation_radius: 0.65 # max. distance from an obstacle at which costs are incurred for planning paths. + inflation_radius: 0.70 # max. distance from an obstacle at which costs are incurred for planning paths. voxel_layer: plugin: "nav2_costmap_2d::VoxelLayer" enabled: True diff --git a/docker-compose.yaml b/docker-compose.yaml index 22ca6e5..336370b 100644 --- a/docker-compose.yaml +++ b/docker-compose.yaml @@ -308,6 +308,29 @@ services: - RMW_IMPLEMENTATION=rmw_cyclonedds_cpp - ROS_MASTER_URI=http://localhost:11311 # is configured to run roscore on the robot but could change to local ros1 machine here +## Configure on ROS1 Hosts +# seggy 192.168.0.100 +# locally running ros-package: control1 +# subscribing topic2 +# publishing topic1 + +# robot2 192.168.x.x +# locally running ros-package: control2 +# subscribing topic1 +# publishing topic2 +# As we need one ros-master to control the communication, we choose 192.168.1.1 as master. Therefore we execute locally on robot 1: + +# export ROS_MASTER_URI=http://192.168.0.100:11311 # or localhost? +# export ROS_HOSTNAME=192.168.0.100 +# export ROS_IP=192.168.0.100 +# roscore + +# In order to connect to the ROS-master, we execute locally on robot2: + +# export ROS_MASTER_URI=http://192.1.1.1:11311 +# export ROS_IP=192.168.1.2 +# export ROS_HOSTNAME=192.168.1.2 + # ROS2 oak-d-lite camera oakd: extends: overlay