Skip to content
This repository has been archived by the owner on Sep 24, 2024. It is now read-only.

added webots #1

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .env
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,5 @@ LIDAR_BAUDRATE=256000
DDS_CONFIG=DEFAULT
# DDS_CONFIG=HUSARNET_SIMPLE_AUTO

# RMW_IMPLEMENTATION=rmw_fastrtps_cpp
RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
RMW_IMPLEMENTATION=rmw_fastrtps_cpp
# RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
35 changes: 33 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# rosbot-xl-mapping

Create a map of the unknow environment with ROSbot XL controlled in the LAN network or [over the Internet](https://husarion.com/manuals/rosbot/remote-access/).
Create a map of the unknow environment with ROSbot XL controlled in the LAN network or [over the Internet](https://husarion.com/manuals/rosbot/remote-access/).

## Quick Start (real robot)

Expand Down Expand Up @@ -51,7 +51,7 @@ xhost +local:docker && \
docker compose -f compose.pc.yaml up
```

#### Without the gamepad
#### Without the gamepad

```bash
xhost +local:docker && \
Expand Down Expand Up @@ -115,4 +115,35 @@ And inside the running container shell execute:
ros2 run teleop_twist_keyboard teleop_twist_keyboard
```

## Quick Start (Webots simulation)

> **Prerequisites**
>
> The `compose.sim.webots.yaml` file uses NVIDIA Container Runtime. Make sure you have NVIDIA GPU and the [NVIDIA Container Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html) installed.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it possible to run webots without nvidia runtime? For ignition-gazebo simulation we have two configs (the one without nvidia runtime is really really slow though).

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added in readme running without nvidia.


### Run without Nvidia acceleration
Comment or delete line inside the compose file `compose.sim.webots.yaml`.
```bash
# runtime: nvidia
...
# - NVIDIA_VISIBLE_DEVICES=all
# - NVIDIA_DRIVER_CAPABILITIES=all
```

Start the containers in a new terminal:

```bash
xhost +local:docker && \
docker compose -f compose.sim.webots.yaml up
```

And in the second terminal start `telop-twist-keyboard` for manual ROSbot XL control:

```bash
docker exec -it rviz bash
```

And inside the running container shell execute:

```bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard
5 changes: 2 additions & 3 deletions compose.pc.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,11 @@ services:
ipc: host
devices:
- /dev/input
volumes:
volumes:
- ./config/joy2twist.yaml:/joy2twist.yaml
environment:
- DDS_CONFIG
- RMW_IMPLEMENTATION
command: >
command: >
ros2 launch joy2twist gamepad_controller.launch.py
joy2twist_params_file:=/joy2twist.yaml

57 changes: 57 additions & 0 deletions compose.sim.webots.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
services:

rviz:
image: husarion/rviz2:humble-22-12-20
runtime: nvidia
container_name: rviz
network_mode: host
ipc: host
volumes:
- /tmp/.X11-unix:/tmp/.X11-unix:rw
- ./config/rosbot.rviz:/root/.rviz2/default.rviz
environment:
- DDS_CONFIG
- RMW_IMPLEMENTATION
- DISPLAY=${DISPLAY:?err}
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all

rosbot-xl:
image: husarion/webots:galactic
runtime: nvidia
network_mode: host
ipc: host
volumes:
- /tmp/.X11-unix:/tmp/.X11-unix:rw
environment:
- DDS_CONFIG
- RMW_IMPLEMENTATION
- DISPLAY=${DISPLAY:?err}
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
command: ros2 launch webots_ros2_husarion robot_launch.py robot_name:="rosbot_xl"

mapping:
image: husarion/slam-toolbox:humble-22-12-07
network_mode: host
ipc: host
volumes:
- ./config/slam_toolbox_params_webots.yaml:/slam_params.yaml
environment:
- DDS_CONFIG
- RMW_IMPLEMENTATION
command: >
ros2 launch slam_toolbox online_sync_launch.py
slam_params_file:=/slam_params.yaml
use_sim_time:=True

map-saver:
image: husarion/nav2-map-server:humble-22-12-07
network_mode: host
ipc: host
volumes:
- ./maps:/maps
environment:
- DDS_CONFIG
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not sure if DDS_CONFIG is necessary, and if it is, it should be also included in other containers.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added in every service

- RMW_IMPLEMENTATION
command: bash -c "while true; do ros2 run nav2_map_server map_saver_cli --free 0.15 --fmt png -f /maps/map; sleep 5; done"
87 changes: 13 additions & 74 deletions config/rosbot.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ Panels:
Expanded:
- /Global Options1
- /tf1/Frames1
- /scan1/Topic1
Splitter Ratio: 0.6294117569923401
Tree Height: 871
- Class: rviz_common/Selection
Expand Down Expand Up @@ -53,16 +54,10 @@ Visualization Manager:
Value: true
body_link:
Value: false
camera_link:
Value: false
cover_link:
Value: false
fl_range:
Value: false
fl_wheel_link:
Value: true
fr_range:
Value: false
fr_wheel_link:
Value: true
imu_link:
Expand All @@ -73,20 +68,10 @@ Visualization Manager:
Value: false
odom:
Value: false
orbbec_astra_depth_link:
Value: false
orbbec_astra_depth_reference_link:
Value: false
orbbec_astra_link:
Value: false
rl_range:
Value: false
rl_wheel_link:
Value: true
rplidar_a2_link:
Value: false
rr_range:
Value: false
rplidar_s1_link:
Value: true
rr_wheel_link:
Value: true
Marker Scale: 0.4000000059604645
Expand All @@ -97,36 +82,24 @@ Visualization Manager:
Tree:
base_link:
body_link:
camera_link:
orbbec_astra_link:
orbbec_astra_depth_link:
orbbec_astra_depth_reference_link:
{}
cover_link:
rplidar_a2_link:
rplidar_s1_link:
laser:
{}
fl_range:
{}
fl_wheel_link:
{}
fr_range:
{}
fr_wheel_link:
{}
imu_link:
{}
rl_range:
{}
rl_wheel_link:
{}
rr_range:
{}
rr_wheel_link:
{}
map:
odom:
{}
{}
odom:
{}
Update Interval: 0
Value: true
- Alpha: 0.699999988079071
Expand Down Expand Up @@ -180,7 +153,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Best Effort
Value: /scan
Value: /scan_filtered
Use Fixed Frame: true
Use rainbow: true
Value: true
Expand Down Expand Up @@ -211,28 +184,15 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
cover_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_range:
Alpha: 1
Show Axes: false
Show Trail: false
fl_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_range:
Alpha: 1
Show Axes: false
Show Trail: false
fr_wheel_link:
Alpha: 1
Show Axes: false
Expand All @@ -246,37 +206,16 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
orbbec_astra_depth_link:
Alpha: 1
Show Axes: false
Show Trail: false
orbbec_astra_depth_reference_link:
Alpha: 1
Show Axes: false
Show Trail: false
orbbec_astra_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rl_range:
Alpha: 1
Show Axes: false
Show Trail: false
rl_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rplidar_a2_link:
rplidar_s1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rr_range:
Alpha: 1
Show Axes: false
Show Trail: false
rr_wheel_link:
Alpha: 1
Show Axes: false
Expand Down Expand Up @@ -364,13 +303,13 @@ Window Geometry:
Hide Right Dock: false
Navigation 2:
collapsed: false
QMainWindow State: 000000ff00000000fd000000040000000000000176000003a2fc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001a000000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a2000000c700fffffffb0000000c00430061006d00650072006101000001fc000001a40000000000000000fb00000018004e0061007600690067006100740069006f006e00200032000000013e000000c20000012300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065000000020c000000c00000000000000000fb0000000a0049006d0061006700650100000295000001040000000000000000000000010000014f000003a2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003a2000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000970000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000467000003a200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd000000040000000000000176000003a2fc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001a000000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a2000000c700fffffffb0000000c00430061006d00650072006101000001fc000001a40000000000000000fb00000018004e0061007600690067006100740069006f006e00200032000000013e000000c20000012300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065000000020c000000c00000000000000000fb0000000a0049006d0061006700650100000295000001040000000000000000000000010000014f000003a2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003a2000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000970000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000465000003a200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1848
X: 3912
Y: 552
Width: 1846
X: 74
Y: 27
76 changes: 76 additions & 0 deletions config/slam_toolbox_params_webots.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
# This is the second param file for the slam_toolbox. The difference between this and the slam_toolbox_params.yaml is the use_scan_matching param which
# is set to false. Webots has a bugged lidar parser to the LidarScan message type that's why the map is building incorrectly. It looks like every frame
# of map is rotating about the center of the robot. Summing up there is no robot position correction during mapping.

# Follow the issue:
# https://github.com/cyberbotics/webots/issues/5540

slam_toolbox:
ros__parameters:
# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None #HuberLoss

# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: base_link
scan_topic: /scan_filtered
mode: mapping #localization

debug_logging: false
throttle_scans: 1
transform_publish_period: 0.04
map_update_interval: 1.0
resolution: 0.05
max_laser_range: 12.0 #for rastering images
minimum_time_interval: 0.05
transform_timeout: 0.1
tf_buffer_duration: 20.0
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: false

# General Parameters
# The localization correction based on the lidar measurements is turned off because of bug with lidar in webots simulator.
# https://github.com/cyberbotics/webots/issues/5540
use_scan_matching: false
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

still not fixed? :D It would be nice to add a comment that this parameter is changed, and a general one at the beginning of the file, explaining why it is necessary to have a separate config. Also a link to the issue will be nice, so that we can keep track of it, and remove this config once it is solved.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added the comment at the beginning of the file.

use_scan_barycenter: true
minimum_travel_distance: 0.2
minimum_travel_heading: 0.1
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 0.5
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 0.75
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1

# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true

use_sim_time: False