Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Model Submission for CTU-CRAS-NORLAB MARV #886

Merged
Merged
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
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
model.sdf.urdf
meshes/*.blend
meshes/*.blend1
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
cmake_minimum_required(VERSION 3.10)
project(ctu_cras_norlab_marv_sensor_config_1)

find_package(catkin REQUIRED)

catkin_package()

install(DIRECTORY config launch meshes textures urdf worlds
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(FILES model.sdf model.config
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(PROGRAMS
scripts/print_robot_urdf
scripts/yaml_to_xacro_args
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts)
30 changes: 30 additions & 0 deletions submitted_models/ctu_cras_norlab_marv_sensor_config_1/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
# CTU\_CRAS\_NORLAB\_MARV\_SENSOR\_CONFIG\_1

This package contains sensor config 1 of CTU-CRAS-Norlab MARV robot (Mobile Autonomous Rescue Vehicle). The robot has:

- 5 Basler Ace 2 Pro a2A1920-51gcPRO RGB cameras with 86° FOV lenses (Basler C125-0418-5M-P f4mm)
- 2 Basler Ace acA2040-35gc RGB cameras with 138° FOV fisheye lenses (Evetar M118B029520IR)
- Ouster OS0-128 lidar
- 4 TFMini plus point lidars
- IMU Xsens MTI-30
- Gas sensor
- Weight: about 61 kg

## Model files management

This package follows a different workflow for managing SDF and URDF models of the robot than the suggested one. The only and main source of model data is `urdf/marv.xacro` file and the files it includes.

To get the URDF model of the robot, call `scripts/print_robot_urdf` script which prints the robot URDF on stdout. This script is used in `launch/description.launch`.

The SDF model is a regular file committed to this package, but its updates are not
to be done manually. To change the robot model, make changes in the Xacro, and then run script `scripts/update_robot_sdf_ign`, which updates the `model.sdf` file in this repo. The change can then be commited.

There is also script `scripts/update_robot_sdf_gz`, which creates a model.sdf file suitable for use in Gazebo Classic. This can be used to get its much better visualization functionality, i.e. viewing transparent model, wireframe, inertia, centers of gravity etc.

The model is also configured by a set of shared config files located in `config/` directory. It contains YAML files which are loaded in the following order:

- URDF: `common.yaml`, `urdf.yaml`
- SDF for Ignition Gazebo: `common.yaml`, `sim.yaml`, `ign.yaml`
- SDF for Gazebo Classic: `common.yaml`, `sim.yaml`, `gz.yaml`

Other sensor configurations of MARV make use of the robot model defined here, but use customized configuration files to get the right sensor suite.
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
# General configuration and dimensions of MARV

# Geometry
rover_bodyWidth: 0.3600
rover_bodyLength: 0.6000
rover_bodyHeight: 0.2360
rover_bodyEdgeCurvature: 0.0440 # curvature of the front and rear bottom edges
rover_topBoxWidth: 0.2700
rover_topBoxLength: 0.1000
rover_topBoxHeight: 0.1800
rover_topBoxX: 0.06
rover_topBoxLowerStepWidth: 0.0500
rover_topBoxLowerStepHeight: 0.070
rover_topBoxHigherStepWidth: 0.0300
rover_topBoxHigherStepHeight: 0.1250
rover_flipperLength: 0.4980
rover_flipperWidth: 0.0750
rover_flipperBigRadius: 0.1165
rover_flipperSmallRadius: 0.0780
rover_flipperBeltThickness: 0.0180
rover_flipperBodyGap: 0.0305
rover_flipperJointX: 0.2560 # w.r.t. referential frame
rover_flipperJointZ: 0.0000 # w.r.t. referential frame
rover_flipperBaseAngleOffset: 0.0000
has_flippers: True
bullet_antenna_height: 0.2
bullet_antenna_radius: 0.01

# Locomotion
rover_maxTrackSpeed: 1.0 # m/s
rover_maxTrackAcceleration: 3.0 # m/s^2
rover_maxFlipperRotationVelocity: 1.0 # rad/s
rover_maxFlipperRotationEffort: 120 # Nm

# Payload
has_ouster_lidar: True
has_omnicam_vras: True
has_boson_thermocam: False
has_mote_deployer: False
has_cliff_sensors: True

# Mobilicom
has_mobilicom: True
mobilicom_antenna_l_rotation: -0.5
mobilicom_antenna_l_tilt: 0.0
mobilicom_antenna_r_rotation: 0.0
mobilicom_antenna_r_tilt: 0
mobilicom_antennas_length: 0.17
mobilicom_has_antenna_box: False
mobilicom_is_lite: True
mobilicom_parent_link: rear_right_box
mobilicom_pitch: 0
mobilicom_roll: 0
mobilicom_yaw: 1.570796327
mobilicom_shift_x: 0.05
mobilicom_shift_y: 0.3
mobilicom_shift_z: 0.0

# model workarounds
flipper_inflation_ratio: 1.0
flipper_inward_enlargement: 0.0
big_collision_box_on_top: False
big_collision_box_height: 0.4
big_collision_box_width: 0.5
big_collision_box_depth: 0.85
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# Specifics for Gazebo Classic
rendering_target: gz
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# Specifics for Ignition Gazebo
rendering_target: ign
Loading