Skip to content

Commit

Permalink
rosflight_sim to dynamic assignment aircraft params.
Browse files Browse the repository at this point in the history
 - Now pass the aircraft as a ROS launch param by adding
   "aircraft:=anaconda". Default is skyhunter
  • Loading branch information
iandareid committed Mar 4, 2024
1 parent 8ca638a commit 2c5519e
Show file tree
Hide file tree
Showing 6 changed files with 81 additions and 97 deletions.
11 changes: 9 additions & 2 deletions rosflight_sim/launch/fixedwing.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
"""

import os
import sys
from pathlib import Path

import xacro
Expand Down Expand Up @@ -73,6 +74,12 @@ def generate_launch_description():
'ros_log_level', default_value=TextSubstitution(text='info')
)

aircraft = 'skyhunter' # default aircraft

for arg in sys.argv:
if arg.startswith("aircraft:="):
aircraft = arg.split(":=")[1]

# Start simulator
gazebo_launch_include = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -86,12 +93,12 @@ def generate_launch_description():
'gui': gui,
'verbose': verbose,
'world': world_file,
'params_file': os.path.join(get_package_share_directory('rosflight_sim'), 'params/fixedwing.yaml'),
'params_file': os.path.join(get_package_share_directory('rosflight_sim'), f'params/{aircraft}.yaml'),
}.items()
)

# Render xacro file
xacro_filepath_string = os.path.join(get_package_share_directory('rosflight_sim'), 'xacro/fixedwing.urdf.xacro')
xacro_filepath_string = os.path.join(get_package_share_directory('rosflight_sim'), f'xacro/{aircraft}.urdf.xacro')
urdf_filepath_string = os.path.join(get_package_share_directory('rosflight_sim'), 'resources/fixedwing.urdf')
robot_description = xacro.process_file(
xacro_filepath_string, mappings={
Expand Down
10 changes: 5 additions & 5 deletions rosflight_sim/params/anaconda.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@
# Authors: Ian Reid and Phil Tokumaru

# Mass and inertia parameters are defined in fixedwing.urdf.xacro.
# Mass: 2.28
# Jx: 0.141
# Jy: 0.208
# Jz: 0.293
# Jxz: 0.04
# Mass: 4.5
# Jx: 0.24855
# Jy: 0.3784
# Jz: 0.618
# Jxz: 0.06

/fixedwing/rosflight_sil:
ros__parameters:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
C_L_q: 8.7092
C_L_r: 0.0
C_L_delta_a: 0.0
C_L_delta_e: -0.13 # Correct sign?
C_L_delta_e: 0.13 # Correct sign?
C_L_delta_r: 0.0

C_D_O: 0.00445
Expand Down
89 changes: 0 additions & 89 deletions rosflight_sim/params/twin_dream.yaml

This file was deleted.

66 changes: 66 additions & 0 deletions rosflight_sim/xacro/anaconda.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<?xml version="1.0"?>

<!--
Gazebo Fixedwing Definition File
Author: Gary Ellingson
-->

<robot xmlns:xacro="http://ros.org/wiki/xacro" name="fixedwing">
<!-- Properties -->
<xacro:property name="namespace" value="fixedwing"/>
<xacro:property name="use_mesh_file" value="true"/>
<xacro:property name="mesh_file" value="$(arg mesh_file_location)"/>
<xacro:property name="body_width" value="1.8"/>
<xacro:property name="body_height" value="0.1778"/>
<xacro:property name="body_length" value="1.27"/>

<!--Anaconda physical params-->
<xacro:property name="mass" value="4.5"/>
<xacro:property name="Jx" value="0.24855"/>
<xacro:property name="Jy" value="0.3784"/>
<xacro:property name="Jz" value="0.618"/>
<xacro:property name="Jxz" value="0.06"/>

<!-- Instantiate Link and Visual -->
<link name="${namespace}/base_link">
<inertial>
<mass value="${mass}"/>
<origin xyz="0 0 0"/>
<inertia ixx="${Jx}" ixy="0.00" ixz="${Jxz}" iyy="${Jy}" iyz="0.00" izz="${Jz}"/>
</inertial>

<visual name="plane_visual">
<origin xyz="0 0 0" rpy="0 0 1.570796"/>
<geometry>
<xacro:if value="${use_mesh_file}">
<mesh filename="${mesh_file}" scale="1 1 1"/>
</xacro:if>
<xacro:unless value="${use_mesh_file}">
<box size="${body_width} ${body_height} ${body_length}"/>
</xacro:unless>
</geometry>
</visual>

<collision name="plane_collision">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="${body_height}" radius="${body_width}"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0.00</mu>
<mu2>0.00</mu2>
</ode>
</friction>
</surface>
</collision>
</link>

<!-- ROSflight SIL -->
<xacro:include filename="$(find rosflight_sim)/xacro/rosflight_sil.xacro"/>
<xacro:generic_fixedwing namespace="${namespace}" parent_link="${namespace}/base_link"/>

</robot>
File renamed without changes.

0 comments on commit 2c5519e

Please sign in to comment.