Skip to content

Commit

Permalink
Merge pull request #1 from ctu-mrs/add_alien_drone
Browse files Browse the repository at this point in the history
Add alien drone
  • Loading branch information
klaxalk authored Sep 20, 2023
2 parents 03b9564 + a2a5d1b commit 7903ecd
Show file tree
Hide file tree
Showing 4 changed files with 143 additions and 6 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#!/bin/sh
#
# @name DJI F330 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 8000
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
@@ -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_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]]
enable_ground_truth: [False, 'Enable topic with ground truth odometry', [f450, f550, t650, x500, f330, eaglemk2, brus, naki, big_dofec, a300]]
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 Down Expand Up @@ -53,5 +53,5 @@ enable_vio: [False, 'Add a forward-looking fisheye camera and a high frequency I
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]]
disable_motor_crash: [False, 'Disables motor failure after crash with the environment', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec]]
model_package: ["mrs_uav_gazebo_simulation", 'package name for the UAV models', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, a300]]
disable_motor_crash: [False, 'Disables motor failure after crash with the environment', [f330, f450, f550, t650, x500, eaglemk2, brus, naki, big_dofec, a300]]
Original file line number Diff line number Diff line change
Expand Up @@ -439,7 +439,7 @@ limitations under the License.
<enableMotorCrash>{{ enable_motor_crash }}</enableMotorCrash>
</plugin>

<plugin name="motor{{ motor_number }}_speed_republisher_plugin" filename="libMRSGazeboMotorSpeedRepublisherPlugin.so">
<plugin name="motor{{ motor_number }}_speed_republisher_plugin" filename="libMrsGazeboCommonResources_MotorSpeedRepublisherPlugin.so.so">
<robotNamespace/>
<motorSpeedTopic>/motor_speed/{{ motor_number }}</motorSpeedTopic>
</plugin>
Expand Down Expand Up @@ -539,7 +539,107 @@ limitations under the License.
<enableMotorCrash>{{ enable_motor_crash }}</enableMotorCrash>
</plugin>

<plugin name="motor{{ motor_number }}_speed_republisher_plugin" filename="libMRSGazeboMotorSpeedRepublisherPlugin.so">
<plugin name="motor{{ motor_number }}_speed_republisher_plugin" filename="libMrsGazeboCommonResources_MotorSpeedRepublisherPlugin.so">
<robotNamespace/>
<motorSpeedTopic>/motor_speed/{{ motor_number }}</motorSpeedTopic>
</plugin>

<joint name="prop_{{ motor_number }}_joint" type="revolute">
<parent>{{ parent }}</parent>
<child>prop_{{ motor_number }}_link</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
{%- endmacro -%}
<!--}-->

<!-- Prop macro with 2 meshes mrs motor model{-->
{%- macro prop_macro_2_meshes_mrs_motor_model(direction, rotor_velocity_slowdown_sim, motor_constant, moment_constant, parent, mass, radius, time_constant_up, time_constant_down, max_rot_velocity, motor_number, rotor_drag_coefficient, rolling_moment_coefficient, enable_motor_crash, color, mesh_file_1, mesh_file_2, meshes_z_offset, mesh_scale, x, y, z, roll, pitch, yaw, ixx, ixy, ixz, iyy, iyz, izz) -%}
<link name="prop_{{ motor_number }}_link">
<pose>{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}</pose>
<inertial>
<mass>{{ mass }}</mass>
<inertia>
<ixx>{{ ixx }}</ixx>
<ixy>{{ ixy }}</ixy>
<ixz>{{ ixz }}</ixz>
<iyy>{{ iyy }}</iyy>
<iyz>{{ iyz }}</iyz>
<izz>{{ izz }}</izz>
</inertia>
</inertial>
<visual name="visual_1">
<geometry>
<mesh>
<uri>{{ mesh_file_1 }}</uri>
<scale>{{ mesh_scale }}</scale>
</mesh>
</geometry>
</visual>
<visual name="visual_2">
<pose>{{ 0 }} {{ 0 }} {{ meshes_z_offset }} {{ 0 }} {{ 0 }} {{ 0 }}</pose>
<geometry>
<mesh>
<uri>{{ mesh_file_2 }}</uri>
<scale>{{ mesh_scale }}</scale>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/{{ color }}</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<collision name="prop_{{ motor_number }}_link_collision">
<pose>0 0 0 0 {{ rad90 }} 0</pose>
<geometry>
<cylinder>
<length>{{ 2*radius }}</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>

<plugin name="motor{{ motor_number }}_plugin" filename="libMrsGazeboCommonResources_MotorPropModelPlugin.so">
<robotNamespace/>
<jointName>prop_{{ motor_number }}_joint</jointName>
<linkName>prop_{{ motor_number }}_link</linkName>
<turningDirection>{{ direction }}</turningDirection>
<timeConstantUp>{{ time_constant_up }}</timeConstantUp>
<timeConstantDown>{{ time_constant_down }}</timeConstantDown>
<maxRotVelocity>{{ max_rot_velocity }}</maxRotVelocity>
<motorConstant>{{ motor_constant }}</motorConstant>
<momentConstant>{{ moment_constant }}</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>{{ motor_number }}</motorNumber>
<rotorDragCoefficient>{{ rotor_drag_coefficient }}</rotorDragCoefficient>
<rollingMomentCoefficient>{{ rolling_moment_coefficient }}</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/{{ motor_number }}</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>{{ rotor_velocity_slowdown_sim }}</rotorVelocitySlowdownSim>
<enableMotorCrash>{{ enable_motor_crash }}</enableMotorCrash>
</plugin>

<plugin name="motor{{ motor_number }}_speed_republisher_plugin" filename="libMrsGazeboCommonResources_MotorSpeedRepublisherPlugin.so">
<robotNamespace/>
<motorSpeedTopic>/motor_speed/{{ motor_number }}</motorSpeedTopic>
</plugin>
Expand Down Expand Up @@ -610,6 +710,22 @@ limitations under the License.
<rotorVelocitySlowdownSim>{{ rotor_velocity_slowdown_sim }}</rotorVelocitySlowdownSim>
</plugin>
{%- endmacro -%}
<!--}-->

<!-- Fluid resistance macro {-->
{%- macro fluid_resistance_plugin_macro(verbose, model_mass, parent_link, update_rate, uav_body_resistance_x, uav_body_resistance_y, uav_body_resistance_z) -%}
<plugin name="fluid_resistance_plugin" filename="libMrsGazeboCommonResources_FluidResistancePlugin.so">
<robotNamespace/>
<model_mass>{{ model_mass }}</model_mass>
<FluidResistanceTopicName>/fluid_resistance</FluidResistanceTopicName>
<NameLinkToApplyResistance>{{ parent_link }}</NameLinkToApplyResistance>
<rate>{{ update_rate }}</rate>
<res_x>{{ uav_body_resistance_x }}</res_x>
<res_y>{{ uav_body_resistance_y }}</res_y>
<res_z>{{ uav_body_resistance_z }}</res_z>
<verbose>{{ verbose }}</verbose>
</plugin>
{%- endmacro -%}
<!--}-->

<!-- ================================================================== -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
MAVLINK_UDP_BASE_PORT = 14560
LAUNCH_BASE_PORT = 14900
DEFAULT_VEHICLE_TYPE = 't650'
VEHICLE_TYPES = ['f450', 'f550', 't650', 'x500', 'eaglemk2', 'f330', 'brus', 'naki', 'big_dofec']
VEHICLE_TYPES = ['a300', 'f450', 'f550', 't650', 'x500', 'eaglemk2', 'f330', 'brus', 'naki', 'big_dofec']
SPAWNING_DELAY_SECONDS = 6

class MrsDroneSpawner():
Expand Down

0 comments on commit 7903ecd

Please sign in to comment.