-
Notifications
You must be signed in to change notification settings - Fork 1
added webots #1
base: main
Are you sure you want to change the base?
added webots #1
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
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 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Not sure if There was a problem hiding this comment. Choose a reason for hiding this commentThe 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" |
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 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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. There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
There was a problem hiding this comment.
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).
There was a problem hiding this comment.
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.