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

ROS: modify iris example to support sdformat_urdf #56

Merged
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
20 changes: 10 additions & 10 deletions models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version='1.0'?>
<sdf version='1.9'>
<model name='gimbal_small_2d'>
<pose>0 0 0.18 0 0 0</pose>
<link name='base_link'>
<!-- <pose>0 0 0.18 0 0 0</pose> -->
<link name='gimbal_link'>
<inertial>
<mass>0.2</mass>
<inertia>
Expand All @@ -14,11 +14,11 @@
<izz>0.0001</izz>
</inertia>
</inertial>
<visual name='base_main_viz'>
<visual name='gimbal_main_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_main.dae</uri>
<uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/base_main.dae</uri>
</mesh>
</geometry>
<material>
Expand All @@ -27,7 +27,7 @@
<specular>0.01 0.01 0.01 1.0</specular>
</material>
</visual>
<collision name='base_col'>
<collision name='gimbal_col'>
<pose>0.01 0.075 -0.025 0 0 0</pose>
<geometry>
<box>
Expand All @@ -52,7 +52,7 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_arm.dae</uri>
<uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
<material>
Expand All @@ -65,13 +65,13 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_arm.dae</uri>
<uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
</collision>
</link>
<joint name='roll_joint' type='revolute'>
<parent>base_link</parent>
<parent>gimbal_link</parent>
<child>roll_link</child>
<axis>
<xyz>0 0 1</xyz>
Expand Down Expand Up @@ -102,7 +102,7 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
<uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
<material>
Expand All @@ -116,7 +116,7 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
<uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
</collision>
Expand Down
120 changes: 73 additions & 47 deletions models/iris_with_gimbal/model.sdf
Original file line number Diff line number Diff line change
@@ -1,19 +1,20 @@
<?xml version='1.0'?>
<sdf version="1.9">
<model name="iris_with_gimbal">
<include>
<uri>model://iris_with_standoffs</uri>
<include merge="true">
<uri>package://ardupilot_gazebo/models/iris_with_standoffs</uri>
<name>iris</name>
</include>

<include>
<uri>model://gimbal_small_2d</uri>
<include merge="true">
<uri>package://ardupilot_gazebo/models/gimbal_small_2d</uri>
<name>gimbal</name>
<pose>0 -0.01 0.070 1.57 0 1.57</pose>
<pose>0 -0.01 -0.11 1.57 0 1.57</pose>
</include>

<joint name="gimbal_joint" type="revolute">
<parent>iris_with_standoffs::base_link</parent>
<child>gimbal::base_link</child>
<parent>base_link</parent>
<child>gimbal_link</child>
<axis>
<limit>
<lower>0</lower>
Expand All @@ -27,6 +28,22 @@
<plugin filename="gz-sim-joint-state-publisher-system"
name="gz::sim::systems::JointStatePublisher">
</plugin>
<plugin
filename="gz-sim-pose-publisher-system"
name="gz::sim::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>

<plugin
filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
<odom_frame>iris/odom</odom_frame>
<robot_base_frame>iris</robot_base_frame>
<dimensions>3</dimensions>
</plugin>
<plugin filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
<a0>0.3</a0>
Expand All @@ -42,7 +59,7 @@
<cp>0.084 0 0</cp>
<forward>0 1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_0</link_name>
<link_name>rotor_0</link_name>
</plugin>
<plugin filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
Expand All @@ -59,7 +76,7 @@
<cp>-0.084 0 0</cp>
<forward>0 -1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_0</link_name>
<link_name>rotor_0</link_name>
</plugin>

<plugin filename="gz-sim-lift-drag-system"
Expand All @@ -77,7 +94,7 @@
<cp>0.084 0 0</cp>
<forward>0 1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_1</link_name>
<link_name>rotor_1</link_name>
</plugin>
<plugin filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
Expand All @@ -94,7 +111,7 @@
<cp>-0.084 0 0</cp>
<forward>0 -1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_1</link_name>
<link_name>rotor_1</link_name>
</plugin>

<plugin filename="gz-sim-lift-drag-system"
Expand All @@ -112,7 +129,7 @@
<cp>0.084 0 0</cp>
<forward>0 -1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_2</link_name>
<link_name>rotor_2</link_name>
</plugin>
<plugin filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
Expand All @@ -129,7 +146,7 @@
<cp>-0.084 0 0</cp>
<forward>0 1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_2</link_name>
<link_name>rotor_2</link_name>
</plugin>

<plugin filename="gz-sim-lift-drag-system"
Expand All @@ -147,7 +164,7 @@
<cp>0.084 0 0</cp>
<forward>0 -1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_3</link_name>
<link_name>rotor_3</link_name>
</plugin>
<plugin filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
Expand All @@ -164,43 +181,67 @@
<cp>-0.084 0 0</cp>
<forward>0 1 0</forward>
<upward>0 0 1</upward>
<link_name>iris_with_standoffs::rotor_3</link_name>
<link_name>rotor_3</link_name>
</plugin>

<plugin filename="gz-sim-apply-joint-force-system"
name="gz::sim::systems::ApplyJointForce">
<joint_name>iris_with_standoffs::rotor_0_joint</joint_name>
<joint_name>rotor_0_joint</joint_name>
</plugin>
<plugin filename="gz-sim-apply-joint-force-system"
name="gz::sim::systems::ApplyJointForce">
<joint_name>iris_with_standoffs::rotor_1_joint</joint_name>
<joint_name>rotor_1_joint</joint_name>
</plugin>
<plugin filename="gz-sim-apply-joint-force-system"
name="gz::sim::systems::ApplyJointForce">
<joint_name>iris_with_standoffs::rotor_2_joint</joint_name>
<joint_name>rotor_2_joint</joint_name>
</plugin>
<plugin filename="gz-sim-apply-joint-force-system"
name="gz::sim::systems::ApplyJointForce">
<joint_name>iris_with_standoffs::rotor_3_joint</joint_name>
<joint_name>rotor_3_joint</joint_name>
</plugin>

<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>roll_joint</joint_name>
<topic>/gimbal/cmd_roll</topic>
<p_gain>2</p_gain>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>tilt_joint</joint_name>
<topic>/gimbal/cmd_tilt</topic>
<p_gain>2</p_gain>
</plugin>

<plugin filename="gz-sim-linearbatteryplugin-system"
name="gz::sim::systems::LinearBatteryPlugin">
<battery_name>lipo_3500mAh</battery_name>
<fix_issue_225>true</fix_issue_225>
<open_circuit_voltage_constant_coef>12.6</open_circuit_voltage_constant_coef>
<open_circuit_voltage_linear_coef>-2.7</open_circuit_voltage_linear_coef>
<capacity>3.5</capacity>
<voltage>12.6</voltage>
<initial_charge>3.5</initial_charge>
<power_load>200.0</power_load>
<start_draining>false</start_draining>
</plugin>

<plugin name="ArduPilotPlugin"
filename="ArduPilotPlugin">
<!-- Port settings -->
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9002</fdm_port_in>
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<lock_step>1</lock_step>

<!-- Frame conventions
Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates
-->
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<gazeboXYZToNED>0 0 0 3.141593 0 1.57079632</gazeboXYZToNED>

<!-- Sensors -->
<imuName>iris_with_standoffs::imu_link::imu_sensor</imuName>
<imuName>imu_link::imu_sensor</imuName>

<!-- Control channels -->
<!--
incoming control command [0, 1]
so offset it by 0 to get [0, 1]
Expand All @@ -209,7 +250,7 @@
multiplier = 838 max rpm / 1 = 838
-->
<control channel="0">
<jointName>iris_with_standoffs::rotor_0_joint</jointName>
<jointName>rotor_0_joint</jointName>
<useForce>1</useForce>
<multiplier>838</multiplier>
<offset>0</offset>
Expand All @@ -227,7 +268,7 @@
</control>

<control channel="1">
<jointName>iris_with_standoffs::rotor_1_joint</jointName>
<jointName>rotor_1_joint</jointName>
<useForce>1</useForce>
<multiplier>838</multiplier>
<offset>0</offset>
Expand All @@ -245,7 +286,7 @@
</control>

<control channel="2">
<jointName>iris_with_standoffs::rotor_2_joint</jointName>
<jointName>rotor_2_joint</jointName>
<useForce>1</useForce>
<multiplier>-838</multiplier>
<offset>0</offset>
Expand All @@ -263,7 +304,7 @@
</control>

<control channel="3">
<jointName>iris_with_standoffs::rotor_3_joint</jointName>
<jointName>rotor_3_joint</jointName>
<useForce>1</useForce>
<multiplier>-838</multiplier>
<offset>0</offset>
Expand All @@ -281,7 +322,7 @@
</control>

<control channel="4">
<jointName>gimbal::roll_joint</jointName>
<jointName>roll_joint</jointName>
<multiplier>3.14159265</multiplier>
<offset>-0.5</offset>
<servo_min>1100</servo_min>
Expand All @@ -292,7 +333,7 @@
</control>

<control channel="5">
<jointName>gimbal::tilt_joint</jointName>
<jointName>tilt_joint</jointName>
<multiplier>3.14159265</multiplier>
<offset>-0.5</offset>
<servo_min>1100</servo_min>
Expand All @@ -304,20 +345,5 @@

</plugin>

<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>gimbal::roll_joint</joint_name>
<topic>/gimbal/cmd_roll</topic>
<p_gain>2</p_gain>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>gimbal::tilt_joint</joint_name>
<topic>/gimbal/cmd_tilt</topic>
<p_gain>2</p_gain>
</plugin>

</model>
</sdf>
Loading