URDF /xacro more modular. Small gazebo improvements. Updates in README
This commit is contained in:
parent
19e6cd1e2c
commit
886f9a23e8
@ -22,7 +22,7 @@ nao_dcm requires several packages to be installed in order to work properly:
|
||||
* [NaoQi C++ SDK] - **Version 1.14.5**
|
||||
* [ROS MoveIt!] - Used for motion planning
|
||||
* [ROS Control] - **Version >=0.6.0**
|
||||
* [Webots for Nao] - The best simulator so far [optional]
|
||||
* [Webots for Nao] - The best? simulator so far [optional]
|
||||
* [Gazebo] - Work in progress but with satisfactory results (**Version >= 2.2.2 alongside gazebo-ros-pkgs >= 2.3.4 and [gazebo_plugins]**) [optional]
|
||||
* [Nao Robot] - A real working Nao is the best "simulator" you'll ever get!! **Version >= V4.0 and flashed OpenNao OS >= 1.14.5**
|
||||
|
||||
@ -65,6 +65,12 @@ This will **launch Gazebo Simulator** and **trajectory controllers** to simulate
|
||||
Basic Options/Guidelines
|
||||
--------------
|
||||
|
||||
###Gazebo arguments/options
|
||||
|
||||
All properties are located in the [gazebo launch] files (in each body type).
|
||||
|
||||
* **use_pid** - true/false => Choose whether to use pid control in motors or not. Currently, usage without PIDs is highly unstable. Also, PID values REALLY need tuning. So, please contribute to that direction.
|
||||
|
||||
###URDF/XACRO properties
|
||||
|
||||
All properties are located in [robot.xacro] file.
|
||||
@ -111,3 +117,4 @@ Copyright (c) 2014, **Konstantinos Chatzilygeroudis**
|
||||
[ros control]: http://wiki.ros.org/ros_control
|
||||
[gazebo_plugins]: http://www.github.com/costashatz/gazebo_plugins
|
||||
[robot.xacro]: https://github.com/costashatz/nao_dcm/blob/master/nao_dcm_common/nao_dcm_description/urdf/modules/robot.xacro
|
||||
[gazebo launch]: https://github.com/costashatz/nao_dcm/tree/master/nao_dcm_apps/nao_dcm_gazebo/launch
|
||||
|
@ -10,7 +10,7 @@
|
||||
</include>
|
||||
|
||||
<!-- Use PIDs?? -->
|
||||
<arg name="use_pid" value="false"/>
|
||||
<arg name="use_pid" value="true"/>
|
||||
|
||||
<group if="$(arg use_pid)">
|
||||
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
|
||||
|
@ -10,7 +10,7 @@
|
||||
</include>
|
||||
|
||||
<!-- Use PIDs?? -->
|
||||
<arg name="use_pid" value="false"/>
|
||||
<arg name="use_pid" value="true"/>
|
||||
|
||||
<group if="$(arg use_pid)">
|
||||
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
|
||||
|
@ -43,7 +43,7 @@
|
||||
<joint name="${side}ShoulderPitch" type="revolute">
|
||||
<parent link="torso"/>
|
||||
<child link="${side}Shoulder"/>
|
||||
<limit effort="${150.27*14.3/1000.0}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3A}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 ${reflect*0.098} 0.1"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -59,7 +59,7 @@
|
||||
<joint name="${side}ElbowYaw" type="revolute">
|
||||
<parent link="${side}ShoulderDummy"/>
|
||||
<child link="${side}Elbow"/>
|
||||
<limit effort="${150.27*14.3/1000.0}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3A}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0.105 ${reflect*0.015} 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
</joint>
|
||||
@ -78,28 +78,28 @@
|
||||
<joint name="LShoulderRoll" type="revolute">
|
||||
<parent link="LShoulder"/>
|
||||
<child link="LShoulderDummy"/>
|
||||
<limit effort="${173.22*14.3/1000.0}" lower="-0.3142" upper="1.3265" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3B}" lower="-0.3142" upper="1.3265" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
<joint name="RShoulderRoll" type="revolute">
|
||||
<parent link="RShoulder"/>
|
||||
<child link="RShoulderDummy"/>
|
||||
<limit effort="${173.22*14.3/1000.0}" lower="-1.3265" upper="0.3142" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3B}" lower="-1.3265" upper="0.3142" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
<joint name="LElbowRoll" type="revolute">
|
||||
<parent link="LElbow"/>
|
||||
<child link="LElbowDummy"/>
|
||||
<limit effort="${173.22*14.3/1000.0}" lower="-1.5446" upper="-0.0349" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3B}" lower="-1.5446" upper="-0.0349" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
<joint name="RElbowRoll" type="revolute">
|
||||
<parent link="RElbow"/>
|
||||
<child link="RElbowDummy"/>
|
||||
<limit effort="${173.22*14.3/1000.0}" lower="0.0349" upper="1.5446" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3B}" lower="0.0349" upper="1.5446" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
@ -105,7 +105,7 @@
|
||||
<parent link="LElbowDummy"/>
|
||||
<child link="l_wrist"/>
|
||||
<origin rpy="0 0 0" xyz="0.05595 0 0"/>
|
||||
<limit effort="${50.61*9.4/1000.0}" lower="-1.8238" upper="1.8238" velocity="3.0"/>
|
||||
<limit effort="${effort_type2*speed_red_type2A}" lower="-1.8238" upper="1.8238" velocity="3.0"/>
|
||||
</joint>
|
||||
<link name="l_wrist">
|
||||
<xacro:visuals_collisions_wrist_yaw reflect="1" side="L"/>
|
||||
@ -121,7 +121,7 @@
|
||||
<parent link="l_wrist"/>
|
||||
<child link="l_gripper"/>
|
||||
<origin rpy="0 0 0" xyz="0.05775 0 0"/>
|
||||
<limit effort="${36.24*9.4/1000.0}" lower="0.0" upper="1.0" velocity="3.0"/>
|
||||
<limit effort="${effort_type2*speed_red_type2B}" lower="0.0" upper="1.0" velocity="3.0"/>
|
||||
</joint>
|
||||
<link name="l_gripper">
|
||||
<inertial> <!-- dummy values for gazebo -->
|
||||
@ -134,7 +134,7 @@
|
||||
<parent link="RElbowDummy"/>
|
||||
<child link="r_wrist"/>
|
||||
<origin rpy="0 0 0" xyz="0.05595 0 0"/>
|
||||
<limit effort="${50.61*9.4/1000.0}" lower="-1.8238" upper="1.8238" velocity="3.0"/>
|
||||
<limit effort="${effort_type2*speed_red_type2A}" lower="-1.8238" upper="1.8238" velocity="3.0"/>
|
||||
</joint>
|
||||
<link name="r_wrist">
|
||||
<xacro:visuals_collisions_wrist_yaw reflect="-1" side="R"/>
|
||||
@ -150,7 +150,7 @@
|
||||
<parent link="r_wrist"/>
|
||||
<child link="r_gripper"/>
|
||||
<origin rpy="0 0 0" xyz="0.05775 0 0"/>
|
||||
<limit effort="${36.24*9.4/1000.0}" lower="0.0" upper="1.0" velocity="3.0"/>
|
||||
<limit effort="${effort_type2*speed_red_type2B}" lower="0.0" upper="1.0" velocity="3.0"/>
|
||||
</joint>
|
||||
<link name="r_gripper">
|
||||
<inertial> <!-- dummy values for gazebo -->
|
||||
|
@ -4,7 +4,7 @@
|
||||
<joint name="HeadYaw" type="revolute">
|
||||
<parent link="torso"/>
|
||||
<child link="neck"/>
|
||||
<limit effort="${150.27*14.3/1000.0}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3A}" lower="-2.0857" upper="2.0857" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.1265"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
@ -21,7 +21,7 @@
|
||||
<joint name="HeadPitch" type="revolute">
|
||||
<parent link="neck"/>
|
||||
<child link="gaze"/>
|
||||
<limit effort="${173.22*14.3/1000.0}" lower="-0.6720" upper="0.5149" velocity="3.0"/>
|
||||
<limit effort="${effort_type3*speed_red_type3B}" lower="-0.6720" upper="0.5149" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
|
@ -4,7 +4,7 @@
|
||||
<joint name="LHipYawPitch" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="LHipYaw"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-1.145303" upper="0.740810" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-1.145303" upper="0.740810" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0.05 -0.085"/>
|
||||
<axis xyz="0 0.707106 -0.707106"/>
|
||||
</joint>
|
||||
@ -20,7 +20,7 @@
|
||||
<joint name="LHipRoll" type="revolute">
|
||||
<parent link="LHipYaw"/>
|
||||
<child link="LHip"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-0.379472" upper="0.790477" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-0.379472" upper="0.790477" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
</joint>
|
||||
@ -36,7 +36,7 @@
|
||||
<joint name="LHipPitch" type="revolute">
|
||||
<parent link="LHip"/>
|
||||
<child link="LHipDummy"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-1.535889" upper="0.484090" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-1.535889" upper="0.484090" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -52,7 +52,7 @@
|
||||
<joint name="LKneePitch" type="revolute">
|
||||
<parent link="LHipDummy"/>
|
||||
<child link="LKnee"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-0.092346" upper="2.112528" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-0.092346" upper="2.112528" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -68,7 +68,7 @@
|
||||
<joint name="LAnklePitch" type="revolute">
|
||||
<parent link="LKnee"/>
|
||||
<child link="l_ankle"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-1.189516" upper="0.922747" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-1.189516" upper="0.922747" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.1029"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -84,7 +84,7 @@
|
||||
<joint name="LAnkleRoll" type="revolute">
|
||||
<parent link="l_ankle"/>
|
||||
<child link="l_sole"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-0.397880" upper="0.769001" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-0.397880" upper="0.769001" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
</joint>
|
||||
@ -101,7 +101,7 @@
|
||||
<joint name="RHipYawPitch" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="RHipYaw"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-1.145303" upper="0.740810" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-1.145303" upper="0.740810" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 -0.05 -0.085"/>
|
||||
<axis xyz="0 0.707106 0.707106"/>
|
||||
<mimic joint="LHipYawPitch" multiplier="1" offset="0"/>
|
||||
@ -118,7 +118,7 @@
|
||||
<joint name="RHipRoll" type="revolute">
|
||||
<parent link="RHipYaw"/>
|
||||
<child link="RHip"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-0.790477" upper="0.379472" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-0.790477" upper="0.379472" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
</joint>
|
||||
@ -134,7 +134,7 @@
|
||||
<joint name="RHipPitch" type="revolute">
|
||||
<parent link="RHip"/>
|
||||
<child link="RHipDummy"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-1.535889" upper="0.484090" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-1.535889" upper="0.484090" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -150,7 +150,7 @@
|
||||
<joint name="RKneePitch" type="revolute">
|
||||
<parent link="RHipDummy"/>
|
||||
<child link="RKnee"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-0.103083" upper="2.120198" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-0.103083" upper="2.120198" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -166,7 +166,7 @@
|
||||
<joint name="RAnklePitch" type="revolute">
|
||||
<parent link="RKnee"/>
|
||||
<child link="r_ankle"/>
|
||||
<limit effort="${130.85*68/1000.0}" lower="-1.186448" upper="0.932056" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1B}" lower="-1.186448" upper="0.932056" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.1029"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
@ -182,7 +182,7 @@
|
||||
<joint name="RAnkleRoll" type="revolute">
|
||||
<parent link="r_ankle"/>
|
||||
<child link="r_sole"/>
|
||||
<limit effort="${201.3*68/1000.0}" lower="-0.768992" upper="0.397935" velocity="3.0"/>
|
||||
<limit effort="${effort_type1*speed_red_type1A}" lower="-0.768992" upper="0.397935" velocity="3.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
</joint>
|
||||
|
@ -10,6 +10,15 @@
|
||||
<xacro:property name="helmet_cameras_viz" value="false" />
|
||||
<xacro:property name="use_odroid" value="true" />
|
||||
<xacro:property name="use_hector_imu" value="false" />
|
||||
<xacro:property name="effort_type1" value="0.0161" />
|
||||
<xacro:property name="effort_type2" value="0.0049" />
|
||||
<xacro:property name="effort_type3" value="0.0062" />
|
||||
<xacro:property name="speed_red_type1A" value="201.3" />
|
||||
<xacro:property name="speed_red_type1B" value="130.85" />
|
||||
<xacro:property name="speed_red_type2A" value="50.61" />
|
||||
<xacro:property name="speed_red_type2B" value="36.24" />
|
||||
<xacro:property name="speed_red_type3A" value="150.27" />
|
||||
<xacro:property name="speed_red_type3B" value="173.22" />
|
||||
|
||||
<!-- Which IMU plugin to use (hector or default) -->
|
||||
<xacro:if value="${use_hector_imu}">
|
||||
|
@ -7,7 +7,7 @@
|
||||
<actuator name="HeadYaw_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="HeadPitch_Transmission">
|
||||
@ -16,7 +16,7 @@
|
||||
<actuator name="HeadPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<!-- ARMS -->
|
||||
@ -28,7 +28,7 @@
|
||||
<actuator name="${side}ShoulderPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ElbowYaw_Transmission">
|
||||
@ -37,7 +37,7 @@
|
||||
<actuator name="${side}ElbowYaw_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ShoulderRoll_Transmission">
|
||||
@ -46,7 +46,7 @@
|
||||
<actuator name="${side}ShoulderRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ElbowRoll_Transmission">
|
||||
@ -55,7 +55,7 @@
|
||||
<actuator name="${side}ElbowRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</xacro:macro>
|
||||
@ -70,7 +70,7 @@
|
||||
<actuator name="${side}HipYawPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}HipRoll_Transmission">
|
||||
@ -79,7 +79,7 @@
|
||||
<actuator name="${side}HipRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}HipPitch_Transmission">
|
||||
@ -88,7 +88,7 @@
|
||||
<actuator name="${side}HipPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}KneePitch_Transmission">
|
||||
@ -97,7 +97,7 @@
|
||||
<actuator name="${side}KneePitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}AnklePitch_Transmission">
|
||||
@ -106,7 +106,7 @@
|
||||
<actuator name="${side}AnklePitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}AnkleRoll_Transmission">
|
||||
@ -115,7 +115,7 @@
|
||||
<actuator name="${side}AnkleRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</xacro:macro>
|
||||
|
@ -7,7 +7,7 @@
|
||||
<actuator name="HeadYaw_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="HeadPitch_Transmission">
|
||||
@ -16,7 +16,7 @@
|
||||
<actuator name="HeadPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<!-- ARMS -->
|
||||
@ -28,7 +28,7 @@
|
||||
<actuator name="${side}ShoulderPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ElbowYaw_Transmission">
|
||||
@ -37,7 +37,7 @@
|
||||
<actuator name="${side}ElbowYaw_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>150.27</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}WristYaw_Transmission">
|
||||
@ -46,7 +46,7 @@
|
||||
<actuator name="${side}WristYaw_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>50.61</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type2A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}Hand_Transmission">
|
||||
@ -55,7 +55,7 @@
|
||||
<actuator name="${side}Hand_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>36.24</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type2B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ShoulderRoll_Transmission">
|
||||
@ -64,7 +64,7 @@
|
||||
<actuator name="${side}ShoulderRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}ElbowRoll_Transmission">
|
||||
@ -73,7 +73,7 @@
|
||||
<actuator name="${side}ElbowRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>173.22</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type3B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</xacro:macro>
|
||||
@ -88,7 +88,7 @@
|
||||
<actuator name="${side}HipYawPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}HipRoll_Transmission">
|
||||
@ -97,7 +97,7 @@
|
||||
<actuator name="${side}HipRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}HipPitch_Transmission">
|
||||
@ -106,7 +106,7 @@
|
||||
<actuator name="${side}HipPitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}KneePitch_Transmission">
|
||||
@ -115,7 +115,7 @@
|
||||
<actuator name="${side}KneePitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}AnklePitch_Transmission">
|
||||
@ -124,7 +124,7 @@
|
||||
<actuator name="${side}AnklePitch_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>130.85</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1B}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="${side}AnkleRoll_Transmission">
|
||||
@ -133,7 +133,7 @@
|
||||
<actuator name="${side}AnkleRoll_Motor">
|
||||
<!-- Dummy Values -->
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>201.3</mechanicalReduction>
|
||||
<mechanicalReduction>${speed_red_type1A}</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</xacro:macro>
|
||||
|
@ -1,5 +1,35 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- MACROS FOR DISABLE LINKS -->
|
||||
<xacro:macro name="DisabledLinks" params="side side_small">
|
||||
<plugin name="${side}Finger11" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger11</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Finger12" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger12</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Finger13" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger13</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Finger21" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger21</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Finger22" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger22</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Finger23" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Finger23</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Thumb1" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Thumb1</link>
|
||||
</plugin>
|
||||
<plugin name="${side}Thumb2" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side}Thumb2</link>
|
||||
</plugin>
|
||||
<plugin name="${side_small}_gripper" filename="libgazebo_disable_link_plugin.so">
|
||||
<link>${side_small}_gripper</link>
|
||||
</plugin>
|
||||
</xacro:macro>
|
||||
<!-- MACROS FOR MIMIC JOINTS -->
|
||||
<!-- Fingers -->
|
||||
<xacro:macro name="FingerMimics" params="side num">
|
||||
@ -72,6 +102,9 @@
|
||||
|
||||
<xacro:ThumbMimics side="L"/>
|
||||
<xacro:ThumbMimics side="R"/>
|
||||
|
||||
<xacro:DisabledLinks side="L" side_small="l"/>
|
||||
<xacro:DisabledLinks side="R" side_small="r"/>
|
||||
</gazebo>
|
||||
<!-- END OF GAZEBO ROS CONTROL PLUGIN -->
|
||||
<!-- GAZEBO MATERIALS -->
|
||||
|
Loading…
x
Reference in New Issue
Block a user