Files
SpotMicroESP32-Leika/mock/simulator/mini_ros/urdf/spot_accessories.urdf
T
2024-03-04 15:55:45 +01:00

1032 lines
37 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from spot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="spot">
<material name="orange">
<color rgba="1.0 0.5 0.0 1"/>
</material>
<material name="black">
<color rgba="0.1 0.1 0.1 1"/>
</material>
<material name="grey">
<color rgba="0.6 0.6 0.6 1"/>
</material>
<!-- Left Leg: prefix is front or rear -->
<!-- <xacro:macro name="LeftLeg" params="prefix reflect">
<link name="${prefix}_Left_Leg">
<visual>
<geometry>
<box size="${leglen} 0.1 0.2"/>
</geometry>
<origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="${leglen} 0.1 0.2"/>
</geometry>
<origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>
</collision>
<xacro:default_inertial mass="10"/>
</link>
<joint name="base_to_${prefix}_leg" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_leg"/>
<origin xyz="0 ${reflect*(width+.02)} 0.25" />
</joint>
</xacro:macro> -->
<joint name="hokuyo_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.0 0.1"/>
<parent link="base_link"/>
<child link="hokuyo_frame"/>
</joint>
<link name="hokuyo_frame">
<inertial>
<mass value="0.270"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="2.632e-4" ixy="0" ixz="0" iyy="2.632e-4" iyz="0" izz="1.62e-4"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.0115"/>
<geometry>
<box size="0.058 0.058 0.087"/>
<!--<mesh filename="package://hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl"/>-->
</geometry>
</collision>
</link>
<gazebo reference="hokuyo_frame">
<sensor name="hokuyo" type="ray">
<always_on>true</always_on>
<update_rate>30</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>1040</samples>
<resolution>1</resolution>
<min_angle>2.26892802759</min_angle>
<max_angle>-2.26892802759</max_angle>
</horizontal>
</scan>
<range>
<min>0.2</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.004</stddev>
</noise>
</ray>
<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_hokuyo_controller">
<topicName>scan</topicName>
<frameName>hokuyo_frame</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo reference="hokuyo_frame">
<material>Gazebo/FlatBlack</material>
</gazebo>
<!-- <xacro:asus_camera
parent="base_link"
name="camera">
<origin xyz="0.2 0.0 0.05" rpy="0 0 0"/>
</xacro:asus_camera> -->
<gazebo>
<plugin filename="libhector_gazebo_ros_imu.so" name="imu_controller">
<updateRate>50.0</updateRate>
<bodyName>imu_link</bodyName>
<topicName>imu/data</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-09" ixy="0.0" ixz="0.0" iyy="1e-09" iyz="0.0" izz="1e-09"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
</joint>
<!-- <xacro:include filename="$(find champ_arm_description)/urdf/champ_arm.urdf.xacro" />
<xacro:champ_arm parent="base_link">
<origin xyz="0.07 0.0 ${base_z_length / 2}" rpy="0 0 0"/>
</xacro:champ_arm> -->
<!-- Robot description -->
<!-- STATIC Links -->
<link name="base_link"/>
<link name="base_inertia">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0.035 -0.045"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/MAINBODY.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 0"/>
<geometry>
<box size="0.114 0.2 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="0.6"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.0025" ixy="0" ixz="0" iyx="0" iyy="0.0011498" iyz="0" izx="0" izy="0" izz="0.0026498"/>
</inertial>
</link>
<gazebo reference="base_inertia">
<material>Gazebo/Orange</material>
</gazebo>
<!-- m to mm -->
<link name="battery">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.15 0.035 -0.022"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Battery.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 0"/>
<geometry>
<box size="0.048 0.145 0.026"/>
</geometry>
</collision>
<inertial>
<mass value="0.4"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000723366666667" ixy="0" ixz="0" iyx="0" iyy="9.93333333333e-05" iyz="0" izx="0" izy="0" izz="0.000777633333333"/>
</inertial>
</link>
<gazebo reference="battery">
<material>Gazebo/Black</material>
</gazebo>
<!-- m to mm -->
<link name="chassis_left">
<visual>
<origin rpy="0 1.57079632679 -1.57079632679" xyz="0.016 0.003 0"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Chassis_Left_Side.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 -1.57079632679" xyz="0 0 0"/>
<geometry>
<box size="0.06 0.15 0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="1.878e-05" ixy="0" ixz="0" iyx="0" iyy="3.03e-06" iyz="0" izx="0" izy="0" izz="2.175e-05"/>
</inertial>
</link>
<gazebo reference="chassis_left">
<material>Gazebo/Black</material>
</gazebo>
<!-- m to mm -->
<link name="chassis_right">
<visual>
<origin rpy="0 1.57079632679 1.57079632679" xyz="-0.016 -0.003 0"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Chassis_Right_Side.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<box size="0.06 0.15 0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="1.878e-05" ixy="0" ixz="0" iyx="0" iyy="3.03e-06" iyz="0" izx="0" izy="0" izz="2.175e-05"/>
</inertial>
</link>
<gazebo reference="chassis_right">
<material>Gazebo/Black</material>
</gazebo>
<!-- m to mm -->
<link name="front">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0.035 -0.045"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Front.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.16 0 0.006"/>
<geometry>
<box size="0.114 0.045 0.085"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="7.70833333333e-05" ixy="0" ixz="0" iyx="0" iyy="0.000168508333333" iyz="0" izx="0" izy="0" izz="0.000125175"/>
</inertial>
</link>
<gazebo reference="front">
<material>Gazebo/Orange</material>
</gazebo>
<!-- m to mm -->
<link name="back">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0.035 -0.045"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Back.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0 0.006"/>
<geometry>
<box size="0.114 0.075 0.085"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000107083333333" ixy="0" ixz="0" iyx="0" iyy="0.000168508333333" iyz="0" izx="0" izy="0" izz="0.000155175"/>
</inertial>
</link>
<gazebo reference="back">
<material>Gazebo/Orange</material>
</gazebo>
<!-- m to mm -->
<link name="front_bracket">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0.035 -0.045"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Front_Bracket.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.1 0 0"/>
<geometry>
<box size="0.025 0.075 0.085"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000107083333333" ixy="0" ixz="0" iyx="0" iyy="6.54166666667e-05" iyz="0" izx="0" izy="0" izz="5.20833333333e-05"/>
</inertial>
</link>
<gazebo reference="front_bracket">
<material>Gazebo/Black</material>
</gazebo>
<!-- m to mm -->
<link name="back_bracket">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.16 0.035 -0.045"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/Back_Bracket.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.1 0 0"/>
<geometry>
<box size="0.025 0.075 0.085"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000107083333333" ixy="0" ixz="0" iyx="0" iyy="6.54166666667e-05" iyz="0" izx="0" izy="0" izz="5.20833333333e-05"/>
</inertial>
</link>
<gazebo reference="back_bracket">
<material>Gazebo/Black</material>
</gazebo>
<!-- m to mm -->
<link name="front_left_hip">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.25 -0.0044 -0.067"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_HIP.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.015 0.01 -0.01"/>
<geometry>
<box size="0.05 0.065 0.065"/>
</geometry>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 0.075 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000140833333333" ixy="0" ixz="0" iyx="0" iyy="0.000112083333333" iyz="0" izx="0" izy="0" izz="0.000112083333333"/>
</inertial>
</link>
<gazebo reference="front_left_hip">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_left_hip" type="revolute">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.0915 0.0394 0.022"/>
<parent link="front_bracket"/>
<child link="front_left_hip"/>
<limit effort="4.0" lower="-1.04" upper="1.04" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_left_upper_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.252 -0.05 -0.055"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_UPPER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0.02 -0.05"/>
<geometry>
<box size="0.035 0.035 0.11"/>
</geometry>
</collision>
<inertial>
<mass value="0.13"/>
<origin rpy="0 0 0" xyz="-0.005 0.0175 -0.055"/>
<!-- Inertial Axes -->
<inertia ixx="0.000144354166667" ixy="0" ixz="0" iyx="0" iyy="0.000144354166667" iyz="0" izx="0" izy="0" izz="2.65416666667e-05"/>
</inertial>
</link>
<gazebo reference="front_left_upper_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_left_upper_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.0015 0.045 -0.0087"/>
<parent link="front_left_hip"/>
<child link="front_left_upper_leg"/>
<limit effort="4.0" lower="-1.57079632679" upper="2.59" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_left_lower_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.0535"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_LOWER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 -0.06"/>
<geometry>
<box size="0.035 0.035 0.12"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<origin rpy="0 0 0" xyz="-0.01 0 -0.06"/>
<!-- Inertial Axes -->
<inertia ixx="6.51041666667e-05" ixy="0" ixz="0" iyx="0" iyy="6.51041666667e-05" iyz="0" izx="0" izy="0" izz="1.02083333333e-05"/>
</inertial>
</link>
<gazebo reference="front_left_lower_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_left_lower_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="-0.005 0.018 -0.109"/>
<parent link="front_left_upper_leg"/>
<child link="front_left_lower_leg"/>
<limit effort="4.0" lower="-2.9" upper="1.57079632679" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_left_foot">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_FOOT.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_FOOT.stl" scale="1 1 1"/>
</geometry>
<contact_coefficients mu="10.1"/>
</collision>
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="3.52083333333e-06" ixy="0" ixz="0" iyx="0" iyy="2.80208333333e-06" iyz="0" izx="0" izy="0" izz="2.80208333333e-06"/>
</inertial>
</link>
<gazebo reference="front_left_foot">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Orange</material>
</gazebo>
<joint name="front_left_leg_foot" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.1265"/>
<parent link="front_left_lower_leg"/>
<child link="front_left_foot"/>
</joint>
<link name="back_left_hip">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.25 -0.0044 -0.067"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_HIP.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.015 0.01 -0.01"/>
<geometry>
<box size="0.05 0.065 0.065"/>
</geometry>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 0.075 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000140833333333" ixy="0" ixz="0" iyx="0" iyy="0.000112083333333" iyz="0" izx="0" izy="0" izz="0.000112083333333"/>
</inertial>
</link>
<gazebo reference="back_left_hip">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_left_hip" type="revolute">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.1365 0.0394 0.022"/>
<parent link="back_bracket"/>
<child link="back_left_hip"/>
<limit effort="4.0" lower="-1.04" upper="1.04" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_left_upper_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.252 -0.05 -0.055"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_UPPER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0.02 -0.05"/>
<geometry>
<box size="0.035 0.035 0.11"/>
</geometry>
</collision>
<inertial>
<mass value="0.13"/>
<origin rpy="0 0 0" xyz="-0.005 0.0175 -0.055"/>
<!-- Inertial Axes -->
<inertia ixx="0.000144354166667" ixy="0" ixz="0" iyx="0" iyy="0.000144354166667" iyz="0" izx="0" izy="0" izz="2.65416666667e-05"/>
</inertial>
</link>
<gazebo reference="back_left_upper_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_left_upper_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.0015 0.045 -0.0087"/>
<parent link="back_left_hip"/>
<child link="back_left_upper_leg"/>
<limit effort="4.0" lower="-1.57079632679" upper="2.59" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_left_lower_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.0535"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_LOWER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 -0.06"/>
<geometry>
<box size="0.035 0.035 0.12"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<origin rpy="0 0 0" xyz="-0.01 0 -0.06"/>
<!-- Inertial Axes -->
<inertia ixx="6.51041666667e-05" ixy="0" ixz="0" iyx="0" iyy="6.51041666667e-05" iyz="0" izx="0" izy="0" izz="1.02083333333e-05"/>
</inertial>
</link>
<gazebo reference="back_left_lower_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_left_lower_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="-0.005 0.018 -0.109"/>
<parent link="back_left_upper_leg"/>
<child link="back_left_lower_leg"/>
<limit effort="4.0" lower="-2.9" upper="1.57079632679" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_left_foot">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_FOOT.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.247 -0.068 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/LEFT_FOOT.stl" scale="1 1 1"/>
</geometry>
<contact_coefficients mu="10.1"/>
</collision>
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="3.52083333333e-06" ixy="0" ixz="0" iyx="0" iyy="2.80208333333e-06" iyz="0" izx="0" izy="0" izz="2.80208333333e-06"/>
</inertial>
</link>
<gazebo reference="back_left_foot">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Orange</material>
</gazebo>
<joint name="back_left_leg_foot" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.1265"/>
<parent link="back_left_lower_leg"/>
<child link="back_left_foot"/>
</joint>
<link name="front_right_hip">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.25 0.074 -0.067"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_HIP.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.015 -0.01 -0.01"/>
<geometry>
<box size="0.05 0.065 0.065"/>
</geometry>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 -0.075 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000140833333333" ixy="0" ixz="0" iyx="0" iyy="0.000112083333333" iyz="0" izx="0" izy="0" izz="0.000112083333333"/>
</inertial>
</link>
<gazebo reference="front_right_hip">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_right_hip" type="revolute">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.0915 -0.0394 0.022"/>
<parent link="front_bracket"/>
<child link="front_right_hip"/>
<limit effort="4.0" lower="-1.04" upper="1.04" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_right_upper_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.252 0.12 -0.055"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_UPPER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 -0.02 -0.05"/>
<geometry>
<box size="0.035 0.035 0.11"/>
</geometry>
</collision>
<inertial>
<mass value="0.13"/>
<origin rpy="0 0 0" xyz="-0.005 -0.0175 -0.055"/>
<!-- Inertial Axes -->
<inertia ixx="0.000144354166667" ixy="0" ixz="0" iyx="0" iyy="0.000144354166667" iyz="0" izx="0" izy="0" izz="2.65416666667e-05"/>
</inertial>
</link>
<gazebo reference="front_right_upper_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_right_upper_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.0015 -0.045 -0.0087"/>
<parent link="front_right_hip"/>
<child link="front_right_upper_leg"/>
<limit effort="4.0" lower="-1.57079632679" upper="2.59" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_right_lower_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.0535"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_LOWER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 -0.06"/>
<geometry>
<box size="0.035 0.035 0.12"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<origin rpy="0 0 0" xyz="-0.01 0 -0.06"/>
<!-- Inertial Axes -->
<inertia ixx="6.51041666667e-05" ixy="0" ixz="0" iyx="0" iyy="6.51041666667e-05" iyz="0" izx="0" izy="0" izz="1.02083333333e-05"/>
</inertial>
</link>
<gazebo reference="front_right_lower_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_front_right_lower_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="-0.005 -0.018 -0.109"/>
<parent link="front_right_upper_leg"/>
<child link="front_right_lower_leg"/>
<limit effort="4.0" lower="-2.9" upper="1.57079632679" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="front_right_foot">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_FOOT.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_FOOT.stl" scale="1 1 1"/>
</geometry>
<contact_coefficients mu="10.1"/>
</collision>
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="3.52083333333e-06" ixy="0" ixz="0" iyx="0" iyy="2.80208333333e-06" iyz="0" izx="0" izy="0" izz="2.80208333333e-06"/>
</inertial>
</link>
<gazebo reference="front_right_foot">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Orange</material>
</gazebo>
<joint name="front_right_leg_foot" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.1265"/>
<parent link="front_right_lower_leg"/>
<child link="front_right_foot"/>
</joint>
<link name="back_right_hip">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.25 0.074 -0.067"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_HIP.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0.015 -0.01 -0.01"/>
<geometry>
<box size="0.05 0.065 0.065"/>
</geometry>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 -0.075 0"/>
<!-- Inertial Axes -->
<inertia ixx="0.000140833333333" ixy="0" ixz="0" iyx="0" iyy="0.000112083333333" iyz="0" izx="0" izy="0" izz="0.000112083333333"/>
</inertial>
</link>
<gazebo reference="back_right_hip">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_right_hip" type="revolute">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.1365 -0.0394 0.022"/>
<parent link="back_bracket"/>
<child link="back_right_hip"/>
<limit effort="4.0" lower="-1.04" upper="1.04" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_right_upper_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.252 0.12 -0.055"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_UPPER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 -0.02 -0.05"/>
<geometry>
<box size="0.035 0.035 0.11"/>
</geometry>
</collision>
<inertial>
<mass value="0.13"/>
<origin rpy="0 0 0" xyz="-0.005 -0.0175 -0.055"/>
<!-- Inertial Axes -->
<inertia ixx="0.000144354166667" ixy="0" ixz="0" iyx="0" iyy="0.000144354166667" iyz="0" izx="0" izy="0" izz="2.65416666667e-05"/>
</inertial>
</link>
<gazebo reference="back_right_upper_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_right_upper_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.0015 -0.045 -0.0087"/>
<parent link="back_right_hip"/>
<child link="back_right_upper_leg"/>
<limit effort="4.0" lower="-1.57079632679" upper="2.59" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_right_lower_leg">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.0535"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_LOWER_LEG.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="0 0 -0.06"/>
<geometry>
<box size="0.035 0.035 0.12"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<origin rpy="0 0 0" xyz="-0.01 0 -0.06"/>
<!-- Inertial Axes -->
<inertia ixx="6.51041666667e-05" ixy="0" ixz="0" iyx="0" iyy="6.51041666667e-05" iyz="0" izx="0" izy="0" izz="1.02083333333e-05"/>
</inertial>
</link>
<gazebo reference="back_right_lower_leg">
<material>Gazebo/Black</material>
</gazebo>
<joint name="motor_back_right_lower_leg" type="revolute">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="-0.005 -0.018 -0.109"/>
<parent link="back_right_upper_leg"/>
<child link="back_right_lower_leg"/>
<limit effort="4.0" lower="-2.9" upper="1.57079632679" velocity="4.0"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="back_right_foot">
<visual>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_FOOT.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 1.57079632679" xyz="-0.247 0.138 0.18"/>
<geometry>
<mesh filename="package://mini_ros/stl/OpenQuadruped/RIGHT_FOOT.stl" scale="1 1 1"/>
</geometry>
<contact_coefficients mu="10.1"/>
</collision>
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- Inertial Axes -->
<inertia ixx="3.52083333333e-06" ixy="0" ixz="0" iyx="0" iyy="2.80208333333e-06" iyz="0" izx="0" izy="0" izz="2.80208333333e-06"/>
</inertial>
</link>
<gazebo reference="back_right_foot">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Orange</material>
</gazebo>
<joint name="back_right_leg_foot" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.1265"/>
<parent link="back_right_lower_leg"/>
<child link="back_right_foot"/>
</joint>
<joint name="base_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base_inertia"/>
</joint>
<joint name="base_battery" type="fixed">
<origin rpy="0 0 0" xyz="-0.01 0 -0.0225"/>
<parent link="base_link"/>
<child link="battery"/>
</joint>
<joint name="base_left" type="fixed">
<origin rpy="0 0 0" xyz="0.00 0.052 0"/>
<parent link="base_link"/>
<child link="chassis_left"/>
</joint>
<joint name="base_right" type="fixed">
<origin rpy="0 0 0" xyz="0.00 -0.052 0"/>
<parent link="base_link"/>
<child link="chassis_right"/>
</joint>
<joint name="base_front" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="front"/>
</joint>
<joint name="base_back" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="back"/>
</joint>
<joint name="base_front_bracket" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="front_bracket"/>
</joint>
<joint name="base_back_bracket" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="back_bracket"/>
</joint>
<transmission name="front_left_hip_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_left_hip">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_hip_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="front_left_upper_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_left_lower_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_upper_leg_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="front_left_lower_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_left_upper_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_lower_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="front_right_hip_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_right_hip">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_hip_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="front_right_upper_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_right_lower_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_upper_leg_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="front_right_lower_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_front_right_upper_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_lower_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_left_hip_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_left_hip">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_left_hip_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_left_upper_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_left_lower_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_left_upper_leg_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_left_lower_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_left_upper_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_left_lower_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_right_hip_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_right_hip">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_right_hip_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_right_upper_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_right_lower_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_right_upper_leg_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="back_right_lower_leg_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="motor_back_right_upper_leg">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="back_right_lower_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
</robot>