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

Addition of the m690b model to simulation. #4

Merged
merged 1 commit into from
Nov 8, 2023
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,20 @@
#!/bin/sh
#
# @name Holybro X500 SITL
#
# @type Quadcopter x
#
# @maintainer Petr Stibinger <[email protected]>
#

. ${R}etc/init.d/rc.mc_defaults

param set-default MAV_TYPE 2

param set-default BAT1_N_CELLS 6
param set-default BAT1_CAPACITY 22000
param set-default BAT1_V_EMPTY 3.6
param set-default BAT1_V_CHARGED 4.2
param set-default BAT1_V_LOAD_DROP 0.4

set MIXER quad_x
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
uav_mass: 3.5

motor_params:
n_motors: 4
a: 0.1917
b: -0.15

mrs_uav_managers:

constraint_manager:

default_constraints:
gps_garmin: "medium"
gps_baro: "medium"
rtk: "medium"
aloam: "slow"
hector_garmin: "slow"
vio: "slow"
optflow: "slow"
other: "slow"
ground_truth: "medium"
19 changes: 10 additions & 9 deletions ros_packages/mrs_uav_gazebo_simulation/config/spawner_params.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
enable_rangefinder: [False, 'Add a laser rangefinder (Garmin) pointing down', [f450, f550, t650, x500, f330, eaglemk2, brus, naki, big_dofec]]
enable_rangefinder: [False, 'Add a laser rangefinder (Garmin) pointing down', [f450, f550, t650, x500, f330, eaglemk2, brus, naki, big_dofec, m690]]
enable_rangefinder_up: [False, 'Add a laser rangefinder (Garmin) pointing up', [f450, f550, t650, naki]]
enable_teraranger: [False, 'Add a laser rangefinder (Teraranger) to the vehicle', [f450, f550, t650]]
enable_ground_truth: [False, 'Enable topic with ground truth odometry', [f450, f550, t650, x500, f330, eaglemk2, brus, naki, big_dofec, a300]]
enable_ground_truth: [False, 'Enable topic with ground truth odometry', [f450, f550, t650, x500, f330, eaglemk2, brus, naki, big_dofec, a300, m690]]
enable_mobius_camera_front: [False, 'Add mobius camera to the vehicle [1280x720 30hz], pointed to the front', [f450, f550, t650]]
enable_mobius_camera_down: [False, 'Add mobius camera to the vehicle [1280x720 30hz], pointed to the ground', [f450, f550]]
enable_mobius_camera_back_left: [False, 'Add mobius camera to the vehicle [1280x720 30hz], pointed to the back left', [f450, f550]]
Expand All @@ -15,6 +15,7 @@ use_realistic_realsense: [False, 'Enable a more realistic simulation of the Real
enable_whycon_box: [False, 'Add a Whycon box for relative localization', [f450, f550]]
enable_bluefox_camera: [False, 'Add bluefox camera to the vehicle [752x480 50hz]', [f450, f550, t650, x500]]
enable_bluefox_camera_reverse: [False, 'Add bluefox camera to the vehicle [752x480 50hz], rotated by 180 deg', [f450, f550, t650, x500]]
enable_basler_camera_down: [False, 'Add basler dart camera pointing down [1920x1200]', [m690]]
enable_fisheye_camera: [False, 'Add fisheye camera to the vehicle [752x480 180deg 45hz]', [f450]]
enable_magnetic_gripper: [False, 'Add magnetic gripper', [f450, f550, t650]]
enable_scanse_sweep: [False, 'Add Scanse Sweep laser scanner to the vehicle', [f450, f550, t650]]
Expand All @@ -23,15 +24,15 @@ enable_pendulum: [False, 'Add pendulum to the vehicle', [f450, f550, t650]]
enable_teraranger_evo_tower: [False, 'Add the Teraranger Evo Tower laser scanner to the vehicle', [f450, f550, t650]]
enable_timepix: [False, 'Add Timepix radiation detector to the vehicle', [f450, f550, t650]]
enable_timepix3: [False, 'Add Timepix radiation detector to the vehicle', [f450, t650, x500]]
enable_thermal_camera: [False, 'Add thermal camera to the vehicle', [t650]]
enable_thermal_camera: [False, 'Add thermal camera to the vehicle', [t650, m690]]
enable_velodyne: [False, 'Add Velodyne PUCK Lite laser scanner to the vehicle', [f450, f550, t650]]
enable_ouster: [False, 'Add Ouster laser scanner to the vehicle', [f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
ouster_model: ['OS1-16', 'Choose the Ouster model. Options: OS0-32, OS0-64, OS0-128, OS1-16, OS1-32G1, OS1-32, OS1-64, OS1-128, OS2-32, OS2-64, OS2-128', [f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
use_gpu_ray: [False, 'Laser ray casting will be handled by GPU shaders', [f330, f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
enable_ouster: [False, 'Add Ouster laser scanner to the vehicle', [f450, f550, t650, x500, eaglemk2, naki, big_dofec, m690]]
ouster_model: ['OS1-16', 'Choose the Ouster model. Options: OS0-32, OS0-64, OS0-128, OS1-16, OS1-32G1, OS1-32, OS1-64, OS1-128, OS2-32, OS2-64, OS2-128', [f450, f550, t650, x500, eaglemk2, naki, big_dofec, m690]]
use_gpu_ray: [False, 'Laser ray casting will be handled by GPU shaders', [f330, f450, f550, t650, x500, eaglemk2, naki, big_dofec, m690]]
horizontal_samples: [None, 'Override default number of horizontal samples for LiDARs', [f450, f550, t650, x500, naki]]
rotation_freq: [None, 'Override default update rate for LiDARs', [f450, f550, t650, x500, naki]]
enable_light: [False, 'Add light to the vehicle', [f450, f550, t650, x500, naki]]
enable_servo_camera: [False, 'Add camera on virtual servo to the vehicle', [f450, f550, t650, naki]]
enable_servo_camera: [False, 'Add camera on virtual servo to the vehicle', [f450, f550, t650, naki, m690]]
enable_water_gun: [False, 'Add water gun for fire fighting', [t650]]
enable_parachute: [False, 'Add parachute for emergency flight termination', [t650]]
wall_challenge: [False, 'Configuration for the MBZIRC wall challenge (T650 with 2x bluefox down, realsense down pitched, rangefinder down)', [t650]]
Expand All @@ -49,11 +50,11 @@ enable_dual_uv_cameras: [False, 'Add right and left UV cameras on the vehicle',
enable_back_uv_camera: [False, 'Add back UV camera on the vehicle', [f450, x500]]
uvcam_calib_file: [None, 'Specify UV camera calibration different than default one', [f450, f550, t650, x500]]
uvcam_occlusions: [False, 'Enable occlusions for UVDAR simulation (NOTE: THIS REQUIRES A BEEFY COMPUTER)', [f450, f550, t650, x500]]
pos_file: [None, 'Load positions and ids from .csv file with format: [id, x, y, z, heading] or .yaml file with format: [uav_name: \n id: (int) \n x: (float) \n y: (float) \n z: (float) \n heading: (float)]', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec]]
pos_file: [None, 'Load positions and ids from .csv file with format: [id, x, y, z, heading] or .yaml file with format: [uav_name: \n id: (int) \n x: (float) \n y: (float) \n z: (float) \n heading: (float)]', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, m690]]
pos: [None, 'Specify spawn position of the first vehicle in format [x, y, z, heading]. Additional vehicles will spawn in line with 2m x-offset', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec]]
enable_vio: [False, 'Add a forward-looking fisheye camera and a high frequency IMU', [f330, f450]]
enable_vio_down: [False, 'Add a forward-looking fisheye camera and a high frequency IMU', [f330, f450]]
enable_omni_ultrasounds: [False, 'Add omnidirectional ultrasonic sensors (up, down, 4 in horizontal plane)', [naki]]
enable_safety_led: [False, 'Add a safety LED', [naki]]
model_package: ["mrs_uav_gazebo_simulation", 'package name for the UAV models', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, a300]]
model_package: ["mrs_uav_gazebo_simulation", 'package name for the UAV models', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, a300, m690]]
disable_motor_crash: [False, 'Disables motor failure after crash with the environment', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, a300]]
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -261,6 +261,20 @@ limitations under the License.
{%- endmacro -%}
<!--}-->

<!-- Collision cylinder macro {-->
{%- macro collision_cylinder_macro(name, collision_length, collision_radius, x, y, z, roll, pitch, yaw) -%}
<collision name="{{ name }}_collision">
<pose>{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}</pose>
<geometry>
<cylinder>
<length>{{ collision_length }}</length>
<radius>{{ collision_radius }}</radius>
</cylinder>
</geometry>
</collision>
{%- endmacro -%}
<!--}-->

<!-- Leg macro {-->
{%- macro leg_macro(name, mesh_file, mesh_scale, color, parent, x, y, z, roll, pitch, yaw, collision_height, collision_radius) -%}
{{ visual_mesh_macro(
Expand Down Expand Up @@ -2221,7 +2235,6 @@ limitations under the License.
<visualize>0</visualize>
</sensor>
<!--}-->
<!--}-->

</link>

Expand Down Expand Up @@ -2287,6 +2300,41 @@ limitations under the License.
{%- endmacro -%}
<!--}-->

<!-- Macro to add a Basler Dart camera {-->
{%- macro basler_camera_macro(namespace, camera_name, parent_link, frame_rate, hfov, noise, x, y, z, roll, pitch, yaw) -%}
{{ camera_macro(
parent_link = parent_link,
camera_name = camera_name,
parent_frame_name = namespace + "/fcu",
camera_frame_name = namespace + "/" + camera_name + "_optical",
sensor_base_frame_name = namespace + "/" + camera_name,
frame_rate = frame_rate,
horizontal_fov = hfov,
image_width = 1920,
image_height = 1200,
min_distance = 0.02,
max_distance = 80,
noise_mean = 0.0,
noise_stddev = noise,
mesh_file = "model://mrs_robots_description/meshes/sensors/basler_dart.stl",
mesh_scale = "0.001 0.001 0.001",
color = "DarkGrey",
visual_x = 0,
visual_y = 0,
visual_z = 0,
visual_roll = 0,
visual_pitch = 0,
visual_yaw = 0,
x = x,
y = y,
z = z,
roll = roll,
pitch = pitch,
yaw = yaw)
}}
{%- endmacro -%}
<!--}-->

<!-- Macro to add a Fisheye camera {-->
{%- macro fisheye_camera_macro(namespace, camera_name, topic_ns_prefix, parent_link, frame_rate, noise, x, y, z, roll, pitch, yaw) -%}
{{ fisheye_macro(
Expand Down
Loading