Commit cf91bc0c authored by Ricardo Rico Uribe's avatar Ricardo Rico Uribe
Browse files

added pluggin for ardupilot

parent aa02c97d
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="aquanaute">
<material name="blue">
<color rgba="0 0 0.8 1"/>
......@@ -8,7 +8,7 @@
<color rgba="0.8 0 0 1"/>
</material>
<material name="green">
<color rgba="0 0.8 0 1"/>
<color rgba="0 0.8 0 0.5"/>
</material>
<material name="cyan">
<color rgba="0 0.6 0.6 1"/>
......@@ -132,6 +132,23 @@
</visual>
</link>
<link name="propeller_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.01" length="0.02"/>
</geometry>
<material name="green"/>
</visual>
</link>
<link name="sensor_frame_link">
<inertial>
<origin xyz="-0.007 0 0.379" rpy="0 0 0"/>
......@@ -174,10 +191,20 @@
<origin xyz="-0.05 0.7 -0.036" rpy="0 0 0"/>
</joint>
<joint name="motor_platform_joint" type="fixed">
<joint name="motor_platform_joint" type="revolute">
<parent link="platform_link"/>
<child link="motor_link"/>
<origin xyz="-0.91 0.0 -0.09" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="-1" velocity="-1" lower="-0.9" upper="0.9"/>
</joint>
<joint name="propeller_motor_joint" type="revolute">
<parent link="motor_link"/>
<child link="propeller_link"/>
<origin xyz="-0.28 0 -0.42" rpy="0 1.57 0"/>
<axis xyz="0 0 1"/>
<limit effort="-1" velocity="-1" lower="-1e+12" upper="1e+12"/>
</joint>
<joint name="sensor_frame_platform_joint" type="fixed">
......@@ -236,4 +263,51 @@
<material>Gazebo/White</material>
</gazebo>
<!-- * * * GAZEBO Plugins * * * -->
<plugin name="ardupilot_plugin" filename="libArduPilotPlugin.so">
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9002</fdm_port_in>
<fdm_port_out>9003</fdm_port_out>
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<!--<imuName></imuName>-->
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<!--
incoming control command [0, 1]
so offset it by 0 to get [0, 1]
and divide max target by 1.
offset = 0
multiplier = 838 max rpm / 1 = 838
-->
<control channel="0">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>RIC</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>1</cmd_max>
<cmd_min>-1</cmd_min>
<jointName>aquanaute::motor_platform_joint</jointName>
</control>
<control channel="1">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>THOMAS</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>1</cmd_max>
<cmd_min>-1</cmd_min>
<jointName>aquanaute::propeller_motor_joint</jointName>
</control>
</plugin>
</robot>
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from aquanaute_description.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="aquanaute">
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="red">
<color rgba="0.8 0 0 1"/>
</material>
<material name="green">
<color rgba="0 0.8 0 0.5"/>
</material>
<material name="cyan">
<color rgba="0 0.6 0.6 1"/>
</material>
<material name="yellow">
<color rgba="0.8 0.8 0 1"/>
</material>
<material name="purple">
<color rgba="0.5 0 0.5 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<material name="gray">
<color rgba="0.35 0.35 0.35 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- * * * Link Definitions * * * -->
<link name="base_link">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.001"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<link name="platform_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.024 0 -0007"/>
<mass value="16"/>
<inertia ixx="4.206" ixy="0.0" ixz="-0.031" iyy="4.588" iyz="0.0" izz="8.785"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Platform.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Platform.stl"/>
</geometry>
<material name="yellow"/>
</visual>
</link>
<link name="right_hull_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.124 0 -0.168"/>
<mass value="10.45"/>
<inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="left_hull_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.124 0 -0.168"/>
<mass value="10.45"/>
<inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="motor_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.133 0 -0.391"/>
<mass value="6.6"/>
<inertia ixx="0.072" ixy="3.604" ixz="-0.011" iyy="0.111" iyz="5.484" izz="0.042"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
</geometry>
<material name="purple"/>
</visual>
</link>
<link name="propeller_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.01"/>
</geometry>
<material name="green"/>
</visual>
</link>
<link name="sensor_frame_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.007 0 0.379"/>
<mass value="1.8"/>
<inertia ixx="0.308" ixy="0.00" ixz="0.007" iyy="0.297" iyz="0.00" izz="0.022"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/sensor_frame.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aquanaute_description/models/meshes/sensor_frame.stl"/>
</geometry>
<material name="cyan"/>
</visual>
</link>
<!-- * * * Joint Definitions * * * -->
<joint name="platform_base_joint" type="fixed">
<parent link="base_link"/>
<child link="platform_link"/>
<origin rpy="0 0 0" xyz="0 0 0.35"/>
</joint>
<joint name="right_hull_platform_joint" type="fixed">
<parent link="platform_link"/>
<child link="right_hull_link"/>
<origin rpy="0 0 0" xyz="-0.05 -0.7 -0.036"/>
</joint>
<joint name="left_hull_platform_joint" type="fixed">
<parent link="platform_link"/>
<child link="left_hull_link"/>
<origin rpy="0 0 0" xyz="-0.05 0.7 -0.036"/>
</joint>
<joint name="motor_platform_joint" type="revolute">
<parent link="platform_link"/>
<child link="motor_link"/>
<origin rpy="0 0 0" xyz="-0.91 0.0 -0.09"/>
<axis xyz="0 0 1"/>
<limit effort="-1" lower="-0.9" upper="0.9" velocity="-1"/>
</joint>
<joint name="propeller_motor_joint" type="revolute">
<parent link="motor_link"/>
<child link="propeller_link"/>
<origin rpy="0 1.57 0" xyz="-0.28 0 -0.42"/>
<axis xyz="0 0 1"/>
<limit effort="-1" lower="-1e+12" upper="1e+12" velocity="-1"/>
</joint>
<joint name="sensor_frame_platform_joint" type="fixed">
<parent link="platform_link"/>
<child link="sensor_frame_link"/>
<origin rpy="0 0 0" xyz="-0.55 0.0 0.0"/>
</joint>
<!-- * * * GAZEBO Definitions * * * -->
<gazebo reference="base_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="platform_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="right_hull_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="left_hull_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="motor_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="sensor_frame_link">
<kp>100000.0</kp>
<kd>100000.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/White</material>
</gazebo>
<!-- * * * GAZEBO Plugins * * * -->
<plugin filename="libArduPilotPlugin.so" name="ardupilot_plugin">
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9002</fdm_port_in>
<fdm_port_out>9003</fdm_port_out>
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<!--<imuName></imuName>-->
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<!--
incoming control command [0, 1]
so offset it by 0 to get [0, 1]
and divide max target by 1.
offset = 0
multiplier = 838 max rpm / 1 = 838
-->
<control channel="0">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>RIC</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>1</cmd_max>
<cmd_min>-1</cmd_min>
<jointName>aquanaute::motor_platform_joint</jointName>
</control>
<control channel="1">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>THOMAS</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>1</cmd_max>
<cmd_min>-1</cmd_min>
<jointName>aquanaute::propeller_motor_joint</jointName>
</control>
</plugin>
</robot>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment