update g1 xacro files

This commit is contained in:
xiaoliangstd 2024-06-27 21:30:52 +08:00
parent 1d86ed7a95
commit daaf141bb8
9 changed files with 1392 additions and 0 deletions

View File

@ -0,0 +1,125 @@
g1_gazebo:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 1000
torso_controller:
type: unitree_legged_control/UnitreeJointController
joint: torso_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
# left leg Controllers ---------------------------------------
left_hip_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_hip_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_hip_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_hip_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_hip_yaw_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_hip_yaw_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_knee_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_knee_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_ankle_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_ankle_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_ankle_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_ankle_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
# right leg Controllers ---------------------------------------
right_hip_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_hip_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_hip_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_hip_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_hip_yaw_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_hip_yaw_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_knee_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_knee_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_ankle_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_ankle_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_ankle_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_ankle_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
# left arm Controllers ---------------------------------------
left_shoulder_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_shoulder_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_shoulder_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_shoulder_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_shoulder_yaw_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_shoulder_yaw_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_elbow_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_elbow_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
left_elbow_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: left_elbow_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
# right arm Controllers ---------------------------------------
right_shoulder_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_shoulder_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_shoulder_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_shoulder_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_shoulder_yaw_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_shoulder_yaw_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_elbow_pitch_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_elbow_pitch_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
right_elbow_roll_controller:
type: unitree_legged_control/UnitreeJointController
joint: right_elbow_roll_joint
pid: {p: 100.0, i: 0.0, d: 5.0}

View File

@ -0,0 +1,82 @@
<launch>
<arg name="wname" default="earth"/>
<arg name="rname" default="g1"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<arg name="user_debug" default="true"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find unitree_gazebo)/worlds/$(arg wname).world"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(arg dollar)$(arg robot_path)/xacro/robot.xacro'
DEBUG:=$(arg user_debug)"/>
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<!-- Set trunk and joint positions at startup -->
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
args="-urdf -z 0.6 -model $(arg rname)_gazebo -param robot_description -unpause"/>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>
<!-- load the controllers -->
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
torso_controller
left_hip_pitch_controller
left_hip_roll_controller
left_hip_yaw_controller
left_knee_controller
left_ankle_pitch_controller
left_ankle_roll_controller
right_hip_pitch_controller
right_hip_roll_controller
right_hip_yaw_controller
right_knee_controller
right_ankle_pitch_controller
right_ankle_roll_controller
left_shoulder_pitch_controller
left_shoulder_roll_controller
left_shoulder_yaw_controller
left_elbow_pitch_controller
left_elbow_roll_controller
right_shoulder_pitch_controller
right_shoulder_roll_controller
right_shoulder_yaw_controller
right_elbow_pitch_controller
right_elbow_roll_controller
"/>
<!-- convert joint states to TF transforms for rviz, etc -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
</node>
<!-- <node pkg="unitree_gazebo" type="servo" name="servo" required="true" output="screen"/> -->
<!-- load the parameter unitree_controller -->
<include file="$(find unitree_controller)/launch/set_ctrl.launch">
<arg name="rname" value="$(arg rname)"/>
</include>
</launch>

View File

@ -0,0 +1,188 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find g1_description)/xacro/arm_transmission.xacro"/>
<xacro:macro name="arm" params="name mirror">
<joint name="${name}_shoulder_pitch_joint" type="revolute">
<origin xyz="${shoulder_pitch_joint_offset_x} ${mirror*shoulder_pitch_joint_offset_y} ${shoulder_pitch_joint_offset_z}" rpy="${mirror*shoulder_pitch_joint_offset_roll} 0 0"/>
<parent link="torso_link"/>
<child link="${name}_shoulder_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="${shoulder_pitch_joint_position_min}" upper="${shoulder_pitch_joint_position_max}" effort="${shoulder_pitch_joint_torque_max}" velocity="${shoulder_pitch_joint_velocity_max}"/>
</joint>
<link name="${name}_shoulder_pitch_link">
<inertial>
<origin xyz="${shoulder_pitch_link_com_x} ${mirror*shoulder_pitch_link_com_y} ${shoulder_pitch_link_com_z}" rpy="0 0 0"/>
<mass value="${shoulder_pitch_link_mass}"/>
<inertia
ixx="${shoulder_pitch_link_ixx}" ixy="${mirror*shoulder_pitch_link_ixy}" ixz="${shoulder_pitch_link_ixz}"
iyy="${shoulder_pitch_link_iyy}" iyz="${mirror*shoulder_pitch_link_iyz}"
izz="${shoulder_pitch_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_shoulder_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0 ${mirror*0.06} 0" rpy="0 1.5707 0"/>
<geometry>
<cylinder radius="0.03" length="0.065"/>
</geometry>
</collision>
</link>
<joint name="${name}_shoulder_roll_joint" type="revolute">
<origin xyz="${shoulder_roll_joint_offset_x} ${mirror*shoulder_roll_joint_offset_y} ${shoulder_roll_joint_offset_z}" rpy="${mirror*shoulder_roll_joint_offset_roll} 0 0"/>
<parent link="${name}_shoulder_pitch_link"/>
<child link="${name}_shoulder_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="${shoulder_roll_joint_position_min}" upper="${shoulder_roll_joint_position_max}" effort="${shoulder_roll_joint_torque_max}" velocity="${shoulder_roll_joint_velocity_max}"/>
<xacro:if value="${mirror == 1}">
<limit lower="${shoulder_roll_joint_position_min}" upper="${shoulder_roll_joint_position_max}" effort="${shoulder_roll_joint_torque_max}" velocity="${shoulder_roll_joint_velocity_max}"/>
</xacro:if>
<xacro:if value="${mirror == -1}">
<limit lower="${mirror*shoulder_roll_joint_position_max}" upper="${mirror*shoulder_roll_joint_position_min}" effort="${shoulder_roll_joint_torque_max}" velocity="${shoulder_roll_joint_velocity_max}"/>
</xacro:if>
</joint>
<link name="${name}_shoulder_roll_link">
<inertial>
<origin xyz="${shoulder_roll_link_com_x} ${mirror*shoulder_roll_link_com_y} ${shoulder_roll_link_com_z}" rpy="0 0 0"/>
<mass value="${shoulder_roll_link_mass}"/>
<inertia
ixx="${shoulder_roll_link_ixx}" ixy="${mirror*shoulder_roll_link_ixy}" ixz="${shoulder_roll_link_ixz}"
iyy="${shoulder_roll_link_iyy}" iyz="${mirror*shoulder_roll_link_iyz}"
izz="${shoulder_roll_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_shoulder_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="-0.005 ${mirror*0.01} -0.080" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
</link>
<joint name="${name}_shoulder_yaw_joint" type="revolute">
<origin xyz="${shoulder_yaw_joint_offset_x} ${mirror*shoulder_yaw_joint_offset_y} ${shoulder_yaw_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_shoulder_roll_link"/>
<child link="${name}_shoulder_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="${shoulder_yaw_joint_position_min}" upper="${shoulder_yaw_joint_position_max}" effort="${shoulder_yaw_joint_torque_max}" velocity="${shoulder_yaw_joint_velocity_max}"/>
</joint>
<link name="${name}_shoulder_yaw_link">
<inertial>
<origin xyz="${shoulder_yaw_link_com_x} ${mirror*shoulder_yaw_link_com_y} ${shoulder_yaw_link_com_z}" rpy="0 0 0"/>
<mass value="${shoulder_yaw_link_mass}"/>
<inertia
ixx="${shoulder_yaw_link_ixx}" ixy="${mirror*shoulder_yaw_link_ixy}" ixz="${shoulder_yaw_link_ixz}"
iyy="${shoulder_yaw_link_iyy}" iyz="${mirror*shoulder_yaw_link_iyz}"
izz="${shoulder_yaw_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_shoulder_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="-0.0 -0.0 -0.05" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
</link>
<joint name="${name}_elbow_pitch_joint" type="revolute">
<origin xyz="${elbow_pitch_joint_offset_x} ${mirror*elbow_pitch_joint_offset_y} ${elbow_pitch_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_shoulder_yaw_link"/>
<child link="${name}_elbow_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="${elbow_pitch_joint_position_min}" upper="${elbow_pitch_joint_position_max}" effort="${elbow_pitch_joint_torque_max}" velocity="${elbow_pitch_joint_velocity_max}"/>
</joint>
<link name="${name}_elbow_pitch_link">
<inertial>
<origin xyz="${elbow_pitch_link_com_x} ${mirror*elbow_pitch_link_com_y} ${elbow_pitch_link_com_z}" rpy="0 0 0"/>
<mass value="${elbow_pitch_link_mass}"/>
<inertia
ixx="${elbow_pitch_link_ixx}" ixy="${mirror*elbow_pitch_link_ixy}" ixz="${elbow_pitch_link_ixz}"
iyy="${elbow_pitch_link_iyy}" iyz="${mirror*elbow_pitch_link_iyz}"
izz="${elbow_pitch_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_elbow_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.07 -0.0 -0.0" rpy="0 1.5707 0"/>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
</link>
<joint name="${name}_elbow_roll_joint" type="revolute">
<origin xyz="${elbow_roll_joint_offset_x} ${mirror*elbow_roll_joint_offset_y} ${elbow_roll_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_elbow_pitch_link"/>
<child link="${name}_elbow_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="${elbow_roll_joint_position_min}" upper="${elbow_roll_joint_position_max}" effort="${elbow_roll_joint_torque_max}" velocity="${elbow_roll_joint_velocity_max}"/>
</joint>
<link name="${name}_elbow_roll_link">
<inertial>
<origin xyz="${elbow_roll_link_com_x} ${mirror*elbow_roll_link_com_y} ${elbow_roll_link_com_z}" rpy="0 0 0"/>
<mass value="${elbow_roll_link_mass}"/>
<inertia
ixx="${elbow_roll_link_ixx}" ixy="${mirror*elbow_roll_link_ixy}" ixz="${elbow_roll_link_ixz}"
iyy="${elbow_roll_link_iyy}" iyz="${mirror*elbow_roll_link_iyz}"
izz="${elbow_roll_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_elbow_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.09 0.005 -0.0" rpy="0 1.5707 0"/>
<geometry>
<cylinder radius="0.025" length="0.03"/>
</geometry>
</collision>
</link>
<xacro:arm_transmission name="${name}"/>
</xacro:macro>
</robot>

View File

@ -0,0 +1,63 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="arm_transmission" params="name">
<transmission name="${name}_shoulder_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_shoulder_roll_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_shoulder_yaw_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_yaw_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_yaw_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_elbow_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_elbow_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_elbow_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_elbow_roll_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_elbow_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_elbow_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>

View File

@ -0,0 +1,282 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="stick_mass" value="0.00001"/>
<!-- dynamics inertial value-->
<!-- All the value listed here is based on the left side, and the right side only differs in certain aspects. You can check these based on the g1.urdf file.-->
<!-- torso_link -->
<!-- joint -->
<xacro:property name="torso_joint_offset_x" value="0.0"/>
<xacro:property name="torso_joint_offset_y" value="0.0"/>
<xacro:property name="torso_joint_offset_z" value="0.0"/>
<!-- joint limits -->
<xacro:property name="torso_joint_position_min" value="-2.618"/>
<xacro:property name="torso_joint_position_max" value="2.618"/>
<xacro:property name="torso_joint_torque_max" value="88"/>
<xacro:property name="torso_joint_velocity_max" value="32"/>
<!-- link -->
<xacro:property name="torso_link_com_x" value="0.00197122283"/>
<xacro:property name="torso_link_com_y" value="0.00266902037"/>
<xacro:property name="torso_link_com_z" value="0.16936510960"/>
<xacro:property name="torso_link_mass" value="6.33959811"/>
<xacro:property name="torso_link_ixx" value="0.06037082109027"/>
<xacro:property name="torso_link_ixy" value="-0.00010168407055"/>
<xacro:property name="torso_link_ixz" value="0.00069845018092"/>
<xacro:property name="torso_link_iyy" value="0.04355153796551"/>
<xacro:property name="torso_link_iyz" value="0.00034366422728"/>
<xacro:property name="torso_link_izz" value="0.03339981866010"/>
<!-- leg -->
<!-- hip_pitch_link -->
<!-- joint -->
<xacro:property name="hip_pitch_joint_offset_x" value="0"/>
<xacro:property name="hip_pitch_joint_offset_y" value="0.06445"/>
<xacro:property name="hip_pitch_joint_offset_z" value="-0.1027"/>
<xacro:property name="hip_pitch_joint_offset_pitch" value="-0.34907"/>
<!-- joint limits -->
<xacro:property name="hip_pitch_joint_position_min" value="-2.35"/>
<xacro:property name="hip_pitch_joint_position_max" value="3.05"/>
<xacro:property name="hip_pitch_joint_torque_max" value="88"/>
<xacro:property name="hip_pitch_joint_velocity_max" value="32"/>
<!-- link -->
<xacro:property name="hip_pitch_link_com_x" value="0.001962"/>
<xacro:property name="hip_pitch_link_com_y" value="0.049392"/>
<xacro:property name="hip_pitch_link_com_z" value="-0.000941"/>
<xacro:property name="hip_pitch_link_mass" value="1.299"/>
<xacro:property name="hip_pitch_link_ixx" value="0.0013873"/>
<xacro:property name="hip_pitch_link_ixy" value="-1.63E-05"/>
<xacro:property name="hip_pitch_link_ixz" value="-1E-06"/>
<xacro:property name="hip_pitch_link_iyy" value="0.0009059"/>
<xacro:property name="hip_pitch_link_iyz" value="-4.24E-05"/>
<xacro:property name="hip_pitch_link_izz" value="0.0009196"/>
<!-- hip_roll_link -->
<!-- joint -->
<xacro:property name="hip_roll_joint_offset_x" value="0"/>
<xacro:property name="hip_roll_joint_offset_y" value="0.0523"/>
<xacro:property name="hip_roll_joint_offset_z" value="0"/>
<!-- joint limits -->
<xacro:property name="hip_roll_joint_position_min" value="-0.26"/>
<xacro:property name="hip_roll_joint_position_max" value="2.53"/>
<xacro:property name="hip_roll_joint_torque_max" value="88"/>
<xacro:property name="hip_roll_joint_velocity_max" value="32"/>
<!-- link -->
<xacro:property name="hip_roll_link_com_x" value="0.024757"/>
<xacro:property name="hip_roll_link_com_y" value="-0.001036"/>
<xacro:property name="hip_roll_link_com_z" value="-0.086323"/>
<xacro:property name="hip_roll_link_mass" value="1.446"/>
<xacro:property name="hip_roll_link_ixx" value="0.0022702"/>
<xacro:property name="hip_roll_link_ixy" value="-3.7E-06"/>
<xacro:property name="hip_roll_link_ixz" value="-0.0003789"/>
<xacro:property name="hip_roll_link_iyy" value="0.002304"/>
<xacro:property name="hip_roll_link_iyz" value="-1.8E-05"/>
<xacro:property name="hip_roll_link_izz" value="0.0016001"/>
<!-- hip_yaw_link -->
<!-- joint -->
<xacro:property name="hip_yaw_joint_offset_x" value="0.01966"/>
<xacro:property name="hip_yaw_joint_offset_y" value="-0.0012139"/>
<xacro:property name="hip_yaw_joint_offset_z" value="-0.1241"/>
<!-- joint limits -->
<xacro:property name="hip_yaw_joint_position_min" value="-2.75"/>
<xacro:property name="hip_yaw_joint_position_max" value="2.75"/>
<xacro:property name="hip_yaw_joint_torque_max" value="88"/>
<xacro:property name="hip_yaw_joint_velocity_max" value="32"/>
<!-- link -->
<xacro:property name="hip_yaw_link_com_x" value="-0.053554"/>
<xacro:property name="hip_yaw_link_com_y" value="-0.011477"/>
<xacro:property name="hip_yaw_link_com_z" value="-0.14067"/>
<xacro:property name="hip_yaw_link_mass" value="2.052"/>
<xacro:property name="hip_yaw_link_ixx" value="0.0087264"/>
<xacro:property name="hip_yaw_link_ixy" value="-0.0004402"/>
<xacro:property name="hip_yaw_link_ixz" value="-0.0036676"/>
<xacro:property name="hip_yaw_link_iyy" value="0.011374"/>
<xacro:property name="hip_yaw_link_iyz" value="-0.0006654"/>
<xacro:property name="hip_yaw_link_izz" value="0.004279"/>
<!-- knee_link -->
<!-- joint -->
<xacro:property name="knee_joint_offset_x" value="-0.078292"/>
<xacro:property name="knee_joint_offset_y" value="-0.0017335"/>
<xacro:property name="knee_joint_offset_z" value="-0.177225"/>
<xacro:property name="knee_joint_offset_pitch" value="0.5096"/>
<!-- joint limits -->
<xacro:property name="knee_joint_position_min" value="-0.33489"/>
<xacro:property name="knee_joint_position_max" value="2.5449"/>
<xacro:property name="knee_joint_torque_max" value="139"/>
<xacro:property name="knee_joint_velocity_max" value="20"/>
<!-- link -->
<xacro:property name="knee_link_com_x" value="0.005505"/>
<xacro:property name="knee_link_com_y" value="0.006534"/>
<xacro:property name="knee_link_com_z" value="-0.116629"/>
<xacro:property name="knee_link_mass" value="2.252"/>
<xacro:property name="knee_link_ixx" value="0.012443837"/>
<xacro:property name="knee_link_ixy" value="0.000053496"/>
<xacro:property name="knee_link_ixz" value="-0.000437641"/>
<xacro:property name="knee_link_iyy" value="0.012674902"/>
<xacro:property name="knee_link_iyz" value="-0.000682499"/>
<xacro:property name="knee_link_izz" value="0.001986501"/>
<!-- ankle_pitch_link -->
<!-- joint -->
<xacro:property name="ankle_pitch_joint_offset_x" value="0"/>
<xacro:property name="ankle_pitch_joint_offset_y" value="0.0040687"/>
<xacro:property name="ankle_pitch_joint_offset_z" value="-0.30007"/>
<xacro:property name="ankle_pitch_joint_offset_pitch" value="-0.16053"/>
<!-- joint limits -->
<xacro:property name="ankle_pitch_joint_position_min" value="-0.68"/>
<xacro:property name="ankle_pitch_joint_position_max" value="0.73"/>
<xacro:property name="ankle_pitch_joint_torque_max" value="40"/>
<xacro:property name="ankle_pitch_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="ankle_pitch_link_com_x" value="-0.007269"/>
<xacro:property name="ankle_pitch_link_com_y" value="0"/>
<xacro:property name="ankle_pitch_link_com_z" value="0.011137"/>
<xacro:property name="ankle_pitch_link_mass" value="0.074"/>
<xacro:property name="ankle_pitch_link_ixx" value="8.4E-06"/>
<xacro:property name="ankle_pitch_link_ixy" value="0"/>
<xacro:property name="ankle_pitch_link_ixz" value="-2.9E-06"/>
<xacro:property name="ankle_pitch_link_iyy" value="1.89E-05"/>
<xacro:property name="ankle_pitch_link_iyz" value="0"/>
<xacro:property name="ankle_pitch_link_izz" value="1.26E-05"/>
<!-- ankle_roll_link -->
<!-- joint -->
<xacro:property name="ankle_roll_joint_offset_x" value="0"/>
<xacro:property name="ankle_roll_joint_offset_y" value="0"/>
<xacro:property name="ankle_roll_joint_offset_z" value="-0.017558"/>
<!-- joint limits -->
<xacro:property name="ankle_roll_joint_position_max" value="0.2618"/>
<xacro:property name="ankle_roll_joint_position_min" value="-0.2618"/>
<xacro:property name="ankle_roll_joint_velocity_max" value="53"/>
<xacro:property name="ankle_roll_joint_torque_max" value="40"/>
<!-- link -->
<xacro:property name="ankle_roll_link_com_x" value="0.024762"/>
<xacro:property name="ankle_roll_link_com_y" value="2E-05"/>
<xacro:property name="ankle_roll_link_com_z" value="-0.012526"/>
<xacro:property name="ankle_roll_link_mass" value="0.391"/>
<xacro:property name="ankle_roll_link_ixx" value="0.0001552"/>
<xacro:property name="ankle_roll_link_ixy" value="-1E-07"/>
<xacro:property name="ankle_roll_link_ixz" value="7.51E-05"/>
<xacro:property name="ankle_roll_link_iyy" value="0.0010657"/>
<xacro:property name="ankle_roll_link_iyz" value="1E-07"/>
<xacro:property name="ankle_roll_link_izz" value="0.001098"/>
<!-- arm -->
<!-- shoulder_pitch_link -->
<!-- joint -->
<xacro:property name="shoulder_pitch_joint_offset_x" value="-0.0025"/>
<xacro:property name="shoulder_pitch_joint_offset_y" value="0.10396"/>
<xacro:property name="shoulder_pitch_joint_offset_z" value="0.25928"/>
<xacro:property name="shoulder_pitch_joint_offset_roll" value="0.27925"/>
<!-- joint limits -->
<xacro:property name="shoulder_pitch_joint_position_min" value="-2.9671"/>
<xacro:property name="shoulder_pitch_joint_position_max" value="2.7925"/>
<xacro:property name="shoulder_pitch_joint_torque_max" value="21"/>
<xacro:property name="shoulder_pitch_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="shoulder_pitch_link_com_x" value="-0.001431"/>
<xacro:property name="shoulder_pitch_link_com_y" value="0.048811"/>
<xacro:property name="shoulder_pitch_link_com_z" value="0.001304"/>
<xacro:property name="shoulder_pitch_link_mass" value="0.713"/>
<xacro:property name="shoulder_pitch_link_ixx" value="0.0004614"/>
<xacro:property name="shoulder_pitch_link_ixy" value="-9.3E-06"/>
<xacro:property name="shoulder_pitch_link_ixz" value="1E-05"/>
<xacro:property name="shoulder_pitch_link_iyy" value="0.0004146"/>
<xacro:property name="shoulder_pitch_link_iyz" value="5.5E-06"/>
<xacro:property name="shoulder_pitch_link_izz" value="0.0004416"/>
<!-- shoulder_roll_link -->
<!-- joint -->
<xacro:property name="shoulder_roll_joint_offset_x" value="0"/>
<xacro:property name="shoulder_roll_joint_offset_y" value="0.052"/>
<xacro:property name="shoulder_roll_joint_offset_z" value="0"/>
<xacro:property name="shoulder_roll_joint_offset_roll" value="-0.27925"/>
<!-- joint limits -->
<xacro:property name="shoulder_roll_joint_position_min" value="-1.5882"/>
<xacro:property name="shoulder_roll_joint_position_max" value="2.2515"/>
<xacro:property name="shoulder_roll_joint_torque_max" value="21"/>
<xacro:property name="shoulder_roll_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="shoulder_roll_link_com_x" value="-0.003415"/>
<xacro:property name="shoulder_roll_link_com_y" value="0.006955"/>
<xacro:property name="shoulder_roll_link_com_z" value="-0.064598"/>
<xacro:property name="shoulder_roll_link_mass" value="0.642"/>
<xacro:property name="shoulder_roll_link_ixx" value="0.0006159"/>
<xacro:property name="shoulder_roll_link_ixy" value="0"/>
<xacro:property name="shoulder_roll_link_ixz" value="-5.6E-06"/>
<xacro:property name="shoulder_roll_link_iyy" value="0.0006835"/>
<xacro:property name="shoulder_roll_link_iyz" value="2.1E-06"/>
<xacro:property name="shoulder_roll_link_izz" value="0.000373"/>
<!-- shoulder_yaw_link -->
<!-- joint -->
<xacro:property name="shoulder_yaw_joint_offset_x" value="-0.00354"/>
<xacro:property name="shoulder_yaw_joint_offset_y" value="0.0062424"/>
<xacro:property name="shoulder_yaw_joint_offset_z" value="-0.1032"/>
<!-- joint limits -->
<xacro:property name="shoulder_yaw_joint_position_min" value="-2.618"/>
<xacro:property name="shoulder_yaw_joint_position_max" value="2.618"/>
<xacro:property name="shoulder_yaw_joint_torque_max" value="21"/>
<xacro:property name="shoulder_yaw_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="shoulder_yaw_link_com_x" value="0.000375"/>
<xacro:property name="shoulder_yaw_link_com_y" value="-0.00444"/>
<xacro:property name="shoulder_yaw_link_com_z" value="-0.072374"/>
<xacro:property name="shoulder_yaw_link_mass" value="0.713"/>
<xacro:property name="shoulder_yaw_link_ixx" value="0.0009699"/>
<xacro:property name="shoulder_yaw_link_ixy" value="7.1E-06"/>
<xacro:property name="shoulder_yaw_link_ixz" value="7.8E-06"/>
<xacro:property name="shoulder_yaw_link_iyy" value="0.0009691"/>
<xacro:property name="shoulder_yaw_link_iyz" value="-4.49E-05"/>
<xacro:property name="shoulder_yaw_link_izz" value="0.0003826"/>
<!-- elbow_pitch_link -->
<!-- joint -->
<xacro:property name="elbow_pitch_joint_offset_x" value="0"/>
<xacro:property name="elbow_pitch_joint_offset_y" value="0.00189"/>
<xacro:property name="elbow_pitch_joint_offset_z" value="-0.0855"/>
<!-- joint limits -->
<xacro:property name="elbow_pitch_joint_position_min" value="-0.2268"/>
<xacro:property name="elbow_pitch_joint_position_max" value="3.4208"/>
<xacro:property name="elbow_pitch_joint_torque_max" value="21"/>
<xacro:property name="elbow_pitch_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="elbow_pitch_link_com_x" value="0.064497"/>
<xacro:property name="elbow_pitch_link_com_y" value="0.002873"/>
<xacro:property name="elbow_pitch_link_com_z" value="0"/>
<xacro:property name="elbow_pitch_link_mass" value="0.601"/>
<xacro:property name="elbow_pitch_link_ixx" value="0.0002845"/>
<xacro:property name="elbow_pitch_link_ixy" value="8.06E-05"/>
<xacro:property name="elbow_pitch_link_ixz" value="9E-09"/>
<xacro:property name="elbow_pitch_link_iyy" value="0.0004647"/>
<xacro:property name="elbow_pitch_link_iyz" value="5E-09"/>
<xacro:property name="elbow_pitch_link_izz" value="0.0004712"/>
<!-- elbow_roll_link -->
<!-- joint -->
<xacro:property name="elbow_roll_joint_offset_x" value="0.1"/>
<xacro:property name="elbow_roll_joint_offset_y" value="0"/>
<xacro:property name="elbow_roll_joint_offset_z" value="0"/>
<!-- joint limits -->
<xacro:property name="elbow_roll_joint_position_min" value="-2.0943"/>
<xacro:property name="elbow_roll_joint_position_max" value="2.0943"/>
<xacro:property name="elbow_roll_joint_torque_max" value="21"/>
<xacro:property name="elbow_roll_joint_velocity_max" value="53"/>
<!-- link -->
<xacro:property name="elbow_roll_link_com_x" value="0.081811"/>
<xacro:property name="elbow_roll_link_com_y" value="0.001454"/>
<xacro:property name="elbow_roll_link_com_z" value="0.001"/>
<xacro:property name="elbow_roll_link_mass" value="0.227"/>
<xacro:property name="elbow_roll_link_ixx" value="0.0001093"/>
<xacro:property name="elbow_roll_link_ixy" value="-1.55E-05"/>
<xacro:property name="elbow_roll_link_ixz" value="-2.91E-05"/>
<xacro:property name="elbow_roll_link_iyy" value="0.000977"/>
<xacro:property name="elbow_roll_link_iyz" value="1E-06"/>
<xacro:property name="elbow_roll_link_izz" value="0.0009676"/>
</robot>

View File

@ -0,0 +1,40 @@
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/g1_gazebo</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>1000</update_rate>
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>trunk_imu</topicName>
<bodyName>imu_link</bodyName>
<updateRateHZ>1000.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu_link</frameName>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<gazebo reference="base">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="imu_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
</robot>

View File

@ -0,0 +1,252 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find g1_description)/xacro/leg_transmission.xacro"/>
<xacro:macro name="leg" params="name mirror">
<!-- checked -->
<joint name="${name}_hip_pitch_joint" type="revolute">
<origin xyz="${hip_pitch_joint_offset_x} ${mirror*hip_pitch_joint_offset_y} ${hip_pitch_joint_offset_z}" rpy="0 ${hip_pitch_joint_offset_pitch} 0"/>
<parent link="pelvis"/>
<child link="${name}_hip_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="${hip_pitch_joint_position_min}" upper="${hip_pitch_joint_position_max}" effort="${hip_pitch_joint_torque_max}" velocity="${hip_pitch_joint_velocity_max}"/>
</joint>
<!-- Leg -->
<link name="${name}_hip_pitch_link">
<inertial>
<origin xyz="${hip_pitch_link_com_x} ${mirror*hip_pitch_link_com_y} ${hip_pitch_link_com_z}" rpy="0 0 0"/>
<mass value="${hip_pitch_link_mass}"/>
<inertia
ixx="${hip_pitch_link_ixx}" ixy="${mirror*hip_pitch_link_ixy}" ixz="${hip_pitch_link_ixz}"
iyy="${hip_pitch_link_iyy}" iyz="${mirror*hip_pitch_link_iyz}"
izz="${hip_pitch_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_hip_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.2 0.2 0.2 1"/>
</material>
</visual>
<collision>
<origin xyz="-0.005 ${mirror*0.05} 0" rpy="0 1.5707 0"/>
<geometry>
<cylinder radius="0.05" length="0.06"/>
</geometry>
</collision>
</link>
<joint name="${name}_hip_roll_joint" type="revolute">
<origin xyz="${hip_roll_joint_offset_x} ${mirror*hip_roll_joint_offset_y} ${hip_roll_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_hip_pitch_link"/>
<child link="${name}_hip_roll_link"/>
<axis xyz="1 0 0"/>
<xacro:if value="${mirror == 1}">
<limit lower="${hip_roll_joint_position_min}" upper="${hip_roll_joint_position_max}" effort="${hip_roll_joint_torque_max}" velocity="${hip_roll_joint_velocity_max}"/>
</xacro:if>
<xacro:if value="${mirror == -1}">
<limit lower="${mirror*hip_roll_joint_position_max}" upper="${mirror*hip_roll_joint_position_min}" effort="${hip_roll_joint_torque_max}" velocity="${hip_roll_joint_velocity_max}"/>
</xacro:if>
</joint>
<link name="${name}_hip_roll_link">
<inertial>
<origin xyz="${hip_roll_link_com_x} ${mirror*hip_roll_link_com_y} ${hip_roll_link_com_z}" rpy="0 0 0"/>
<mass value="${hip_roll_link_mass}"/>
<inertia
ixx="${hip_roll_link_ixx}" ixy="${mirror*hip_roll_link_ixy}" ixz="${hip_roll_link_ixz}"
iyy="${hip_roll_link_iyy}" iyz="${mirror*hip_roll_link_iyz}"
izz="${hip_roll_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_hip_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.019 -0.0 -0.11" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.070 0.02"/>
</geometry>
</collision>
</link>
<joint name="${name}_hip_yaw_joint" type="revolute">
<origin xyz="${hip_yaw_joint_offset_x} ${mirror*hip_yaw_joint_offset_y} ${hip_yaw_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_hip_roll_link"/>
<child link="${name}_hip_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="${hip_yaw_joint_position_min}" upper="${hip_yaw_joint_position_max}" effort="${hip_yaw_joint_torque_max}" velocity="${hip_yaw_joint_velocity_max}"/>
</joint>
<link name="${name}_hip_yaw_link">
<inertial>
<origin xyz="${hip_yaw_link_com_x} ${mirror*hip_yaw_link_com_y} ${hip_yaw_link_com_z}" rpy="0 0 0"/>
<mass value="${hip_yaw_link_mass}"/>
<inertia
ixx="${hip_yaw_link_ixx}" ixy="${mirror*hip_yaw_link_ixy}" ixz="${hip_yaw_link_ixz}"
iyy="${hip_yaw_link_iyy}" iyz="${mirror*hip_yaw_link_iyz}"
izz="${hip_yaw_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_hip_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="-0.075 0 -0.18" rpy="1.5707 0 0"/>
<geometry>
<cylinder radius="0.045" length="0.06"/>
</geometry>
</collision>
</link>
<joint name="${name}_knee_joint" type="revolute">
<origin xyz="${knee_joint_offset_x} ${mirror*knee_joint_offset_y} ${knee_joint_offset_z}" rpy="0 ${knee_joint_offset_pitch} 0"/>
<parent link="${name}_hip_yaw_link"/>
<child link="${name}_knee_link"/>
<axis xyz="0 1 0"/>
<limit lower="${knee_joint_position_min}" upper="${knee_joint_position_max}" effort="${knee_joint_torque_max}" velocity="${knee_joint_velocity_max}"/>
</joint>
<link name="${name}_knee_link">
<inertial>
<origin xyz="${knee_link_com_x} ${mirror*knee_link_com_y} ${knee_link_com_z}" rpy="0 0 0"/>
<mass value="${knee_link_mass}"/>
<inertia
ixx="${knee_link_ixx}" ixy="${mirror*knee_link_ixy}" ixz="${knee_link_ixz}"
iyy="${knee_link_iyy}" iyz="${mirror*knee_link_iyz}"
izz="${knee_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_knee_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.007 ${mirror*0.005} -0.15" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.015" length="0.15"/>
</geometry>
</collision>
</link>
<joint name="${name}_ankle_pitch_joint" type="revolute">
<origin xyz="${ankle_pitch_joint_offset_x} ${mirror*ankle_pitch_joint_offset_y} ${ankle_pitch_joint_offset_z}" rpy="0 ${ankle_pitch_joint_offset_pitch} 0"/>
<parent link="${name}_knee_link"/>
<child link="${name}_ankle_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="${ankle_pitch_joint_position_min}" upper="${ankle_pitch_joint_position_max}" effort="${ankle_pitch_joint_torque_max}" velocity="${ankle_pitch_joint_velocity_max}"/>
</joint>
<link name="${name}_ankle_pitch_link">
<inertial>
<origin xyz="${ankle_pitch_link_com_x} ${mirror*ankle_pitch_link_com_y} ${ankle_pitch_link_com_z}" rpy="0 0 0"/>
<mass value="${ankle_pitch_link_mass}"/>
<inertia
ixx="${ankle_pitch_link_ixx}" ixy="${mirror*ankle_pitch_link_ixy}" ixz="${ankle_pitch_link_ixz}"
iyy="${ankle_pitch_link_iyy}" iyz="${mirror*ankle_pitch_link_iyz}"
izz="${ankle_pitch_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_ankle_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
</link>
<joint name="${name}_ankle_roll_joint" type="revolute">
<origin xyz="${ankle_roll_joint_offset_x} ${mirror*ankle_roll_joint_offset_y} ${ankle_roll_joint_offset_z}" rpy="0 0 0"/>
<parent link="${name}_ankle_pitch_link"/>
<child link="${name}_ankle_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="${ankle_roll_joint_position_min}" upper="${ankle_roll_joint_position_max}" effort="${ankle_roll_joint_torque_max}" velocity="${ankle_roll_joint_velocity_max}"/>
</joint>
<link name="${name}_ankle_roll_link">
<inertial>
<origin xyz="${ankle_roll_link_com_x} ${mirror*ankle_roll_link_com_y} ${ankle_roll_link_com_z}" rpy="0 0 0"/>
<mass value="${ankle_roll_link_mass}"/>
<inertia
ixx="${ankle_roll_link_ixx}" ixy="${mirror*ankle_roll_link_ixy}" ixz="${ankle_roll_link_ixz}"
iyy="${ankle_roll_link_iyy}" iyz="${mirror*ankle_roll_link_ixz}"
izz="${ankle_roll_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_ankle_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.2 0.2 0.2 1"/>
</material>
</visual>
<!-- <collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/${name}_ankle_roll_link.STL"/>
</geometry>
</collision> -->
<collision>
<origin xyz="-0.07 0.03 -0.03" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.07 -0.03 -0.03" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
<collision>
<origin xyz="0.14 0.03 -0.03" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
<collision>
<origin xyz="0.14 -0.03 -0.03" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.060 0.010 0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.060 -0.010 0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.003"/>
</geometry>
</collision>
</link>
<xacro:leg_transmission name="${name}"/>
</xacro:macro>
</robot>

View File

@ -0,0 +1,75 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="leg_transmission" params="name">
<transmission name="${name}_hip_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_hip_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_hip_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_hip_roll_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_hip_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_hip_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_hip_yaw_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_hip_yaw_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_hip_yaw_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_knee_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_knee_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_knee_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_ankle_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_ankle_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_ankle_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_ankle_roll_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_ankle_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_ankle_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>

View File

@ -0,0 +1,285 @@
<?xml version="1.0"?>
<robot name="g1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="DEBUG" default="false"/>
<xacro:include filename="$(find g1_description)/xacro/gazebo.xacro"/>
<xacro:include filename="$(find g1_description)/xacro/const.xacro"/>
<xacro:include filename="$(find g1_description)/xacro/leg.xacro"/>
<xacro:include filename="$(find g1_description)/xacro/arm.xacro"/>
<!-- Rotor related joint and link is only for demonstrate location. -->
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<xacro:if value="$(arg DEBUG)">
<link name="world"/>
<joint name="base_static_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.5"/>
<parent link="world"/>
<child link="pelvis"/>
</joint>
</xacro:if>
<!-- Torso -->
<link name="torso_link">
<inertial>
<origin xyz="${torso_link_com_x} ${torso_link_com_y} ${torso_link_com_z}" rpy="0 0 0"/>
<mass value="${torso_link_mass}"/>
<inertia
ixx="${torso_link_ixx}" ixy="${torso_link_ixy}" ixz="${torso_link_ixz}"
iyy="${torso_link_iyy}" iyz="${torso_link_iyz}"
izz="${torso_link_izz}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/torso_link.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.055 0.055 -0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.055 -0.055 -0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.055 0.055 -0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.055 -0.055 -0.020" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.063 0.088 0.065" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.063 -0.088 0.065" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.063 0.088 0.065" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.063 -0.088 0.065" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.063 0.088 0.30" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.063 -0.088 0.30" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.066 0.088 0.30" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.066 -0.088 0.30" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
</link>
<joint name="torso_joint" type="revolute">
<origin xyz="${torso_joint_offset_x} ${torso_joint_offset_y} ${torso_joint_offset_z}" rpy="0 0 0"/>
<parent link="pelvis"/>
<child link="torso_link"/>
<axis xyz="0 0 1"/>
<limit lower="${torso_joint_position_min}" upper="${torso_joint_position_max}" effort="${torso_joint_torque_max}" velocity="${torso_joint_velocity_max}"/>
</joint>
<link name="pelvis">
<inertial>
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
<mass value="2.86"/>
<inertia ixx="0.0079143" ixy="0" ixz="1.6E-06" iyy="0.0069837" iyz="0" izz="0.0059404"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/pelvis.STL"/>
</geometry>
<material name="">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin xyz="0.050 0.060 -0.060" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.050 -0.060 -0.060" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.050 0.060 -0.060" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.050 -0.060 -0.060" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.050 0.060 -0.135" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.050 -0.060 -0.135" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.050 0.060 -0.135" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.050 -0.060 -0.135" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
</link>
<link name="pelvis_contour_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/pelvis_contour_link.STL"/>
</geometry>
<material name="">
<color rgba="0.2 0.2 0.2 1"/>
</material>
</visual>
</link>
<joint name="pelvis_contour_joint" type="fixed">
<parent link="pelvis"/>
<child link="pelvis_contour_link"/>
</joint>
<!-- Head -->
<link name="head_link">
<inertial>
<origin xyz="0.00138066852 0.00028430950 0.42034187824" rpy="0 0 0"/>
<mass value="1.17976522"/>
<inertia ixx="0.00543236042361" ixy="0.00000140137425" ixz="0.00034554752228" iyy="0.00552885306699" iyz="0.00001501216392" izz="0.00165378108136"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://g1_description/meshes/head_link.STL"/>
</geometry>
<material name="">
<color rgba="0.2 0.2 0.2 1"/>
</material>
</visual>
<collision>
<origin xyz="0.055 0.055 0.48" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="0.055 -0.055 0.48" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.055 0.040 0.48" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
<collision>
<origin xyz="-0.055 -0.040 0.48" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
</link>
<joint name="head_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="torso_link"/>
<child link="head_link"/>
</joint>
<!-- IMU -->
<link name="imu_link"></link>
<joint name="imu_joint" type="fixed">
<origin xyz="-0.04233868314 0.00166 0.152067" rpy="0 0 0"/>
<parent link="torso_link"/>
<child link="imu_link"/>
</joint>
<xacro:leg name="left" mirror="1"/>
<xacro:leg name="right" mirror="-1"/>
<xacro:arm name="left" mirror="1"/>
<xacro:arm name="right" mirror="-1"/>
<transmission name="torso_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="torso_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="torso_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>