Skip to content

Commit

Permalink
Merge branch 'master' into Qorvo-dw1000-plugin-and-holder-for-x500
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk authored Nov 9, 2023
2 parents bdf82db + ac1eaf7 commit 63cb676
Show file tree
Hide file tree
Showing 36 changed files with 1,258 additions and 107 deletions.
Binary file added .fig/m690_simulation.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
4 changes: 2 additions & 2 deletions .github/workflows/ros_build_test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ on:
paths-ignore:
- '**/README.md'

pull_request:
branches: [ master ]
pull_request:
branches: [ master ]

workflow_dispatch:

Expand Down
17 changes: 9 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,15 @@ Metapackage for the MRS UAV Gazebo simulation pipeline.

## Unmanned Aerial Vehicles

| Model | Spawn argument | Simulation |
|--------------|----------------|-------------------------------|
| DJI f330 | `--f330` | ![](.fig/f330_simulation.jpg) |
| DJI f450 | `--f450` | ![](.fig/f450_simulation.jpg) |
| Holybro x500 | `--x500` | ![](.fig/x500_simulation.jpg) |
| DJI f550 | `--f550` | ![](.fig/f550_simulation.jpg) |
| Tarot t650 | `--t650` | ![](.fig/t650_simulation.jpg) |
| NAKI II | `--naki` | ![](.fig/naki_simulation.jpg) |
| Model | Spawn argument | Simulation |
|---------------|----------------|-------------------------------|
| DJI f330 | `--f330` | ![](.fig/f330_simulation.jpg) |
| DJI f450 | `--f450` | ![](.fig/f450_simulation.jpg) |
| Holybro x500 | `--x500` | ![](.fig/x500_simulation.jpg) |
| DJI f550 | `--f550` | ![](.fig/f550_simulation.jpg) |
| Tarot t650 | `--t650` | ![](.fig/t650_simulation.jpg) |
| T-Drones m690 | `--m690` | ![](.fig/m690_simulation.jpg) |
| NAKI II | `--naki` | ![](.fig/naki_simulation.jpg) |

## Starting the simulation

Expand Down
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
Expand Up @@ -6,9 +6,9 @@ motor_params:
b: -0.17647

# these model parameters can be used when
# - 'attitude rate', and/or
# - 'control group', and/or
# - 'actuator control'
# are done by the MRS system.
# are accepted by the HW API.
model_params:

arm_length: 0.165 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ motor_params:
b: -0.17647

# these model parameters can be used when
# - 'attitude rate', and/or
# - 'control group', and/or
# - 'actuator control'
# are done by the MRS system.
# are accepted by the HW API.
model_params:

arm_length: 0.225 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ motor_params:
b: -0.17647

# these model parameters can be used when
# - 'attitude rate', and/or
# - 'control group', and/or
# - 'actuator control'
# are done by the MRS system.
# are accepted by the HW API.
model_params:

arm_length: 0.27 # [m]
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
uav_mass: 4.65

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

# these model parameters can be used when
# - 'control group', and/or
# - 'actuator control'
# are accepted by the HW API.
model_params:

arm_length: 0.345 # [m]
body_height: 0.20 # [m]

propulsion:

# force [N] = force_constant * rpm^2
force_constant: 0.00000096809

# torque [Nm] = torque_constant * force [N]
torque_constant: 0.07

prop_radius: 0.2286 # [m]

# allocation motors -> torques

# quadrotor X configuration
# hexarotor X configuration
# [roll torque, [ [RPM_1^2,
# pitch torque, = Alloc * RPM_2^2,
# yaw torque, Matrix ...
# thrust force] ] RPM_n_motors^2]
allocation_matrix: [
-0.707, 0.707, 0.707, -0.707, # *= force_constant*arm_length
-0.707, 0.707, -0.707, 0.707, # *= force_constant*arm_length
-1, -1, 1, 1, # *= torque_constant*force_constant
1, 1, 1, 1, # *= force_constant
]

# The UAV's inertia is approximated as a cilinder using the parameters above
# Alternatively, you can provide inertia matrix directly using the following parameter:
# inertia_matrix: []

rpm:
min: 801.55 # [revolutions/minute]
max: 5337.0 # [revolutions/minute]

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"
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ motor_params:
b: -0.17647

# these model parameters can be used when
# - 'attitude rate', and/or
# - 'control group', and/or
# - 'actuator control'
# are done by the MRS system.
# are accepted by the HW API.
model_params:

arm_length: 0.325 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ motor_params:
b: -0.17647

# these model parameters can be used when
# - 'attitude rate', and/or
# - 'control group', and/or
# - 'actuator control'
# are done by the MRS system.
# are accepted by the HW API.
model_params:

arm_length: 0.25 # [m]
Expand Down
21 changes: 12 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,13 +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 @@ -47,13 +50,13 @@ 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]]
enable_qorvo_dw1000: [False, 'Add Qorvo DW1000 UWB transceiver', [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, m690]]
uwb_id: [0, 'Set id for uwb ranging', [x500]]
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.
Loading

0 comments on commit 63cb676

Please sign in to comment.