-
Notifications
You must be signed in to change notification settings - Fork 60
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
rosflight_sim to dynamic assignment aircraft params.
- Now pass the aircraft as a ROS launch param by adding "aircraft:=anaconda". Default is skyhunter
- Loading branch information
Showing
6 changed files
with
81 additions
and
97 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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.