add fake rotor links
This commit is contained in:
parent
e547e583e5
commit
e02c996261
|
@ -5,6 +5,7 @@ Panels:
|
|||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /RobotModel1
|
||||
- /TF1/Frames1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 530
|
||||
|
@ -23,7 +24,6 @@ Panels:
|
|||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
|
@ -52,7 +52,7 @@ Visualization Manager:
|
|||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
- Alpha: 0.5
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
|
@ -66,6 +66,11 @@ Visualization Manager:
|
|||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
|
@ -76,16 +81,31 @@ Visualization Manager:
|
|||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
|
@ -96,17 +116,32 @@ Visualization Manager:
|
|||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
RL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
|
@ -117,16 +152,31 @@ Visualization Manager:
|
|||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
|
@ -137,11 +187,21 @@ Visualization Manager:
|
|||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
|
@ -163,18 +223,21 @@ Visualization Manager:
|
|||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/Axes
|
||||
- Alpha: 1
|
||||
Class: rviz/Axes
|
||||
Enabled: false
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: <Fixed Frame>
|
||||
Show Trail: false
|
||||
Value: false
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: false
|
||||
Marker Alpha: 1
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
|
@ -212,25 +275,25 @@ Visualization Manager:
|
|||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 9.812193870544434
|
||||
Distance: 1.7572907209396362
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: -0.041462767869234085
|
||||
Y: -0.411843866109848
|
||||
Z: 0.29937663674354553
|
||||
X: 0.18471483886241913
|
||||
Y: -0.16858524084091187
|
||||
Z: -0.1451287716627121
|
||||
Focal Shape Fixed Size: false
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.03979745879769325
|
||||
Pitch: 0.609795868396759
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 1.2935912609100342
|
||||
Yaw: 4.128592014312744
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
|
@ -238,7 +301,7 @@ Window Geometry:
|
|||
Height: 759
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001b90000029dfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000029d000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065000000000000000640000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003ae0000029d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001b90000029dfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000029d000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d00650000000000000006400000042800fffffffb0000000800540069006d00650100000000000004500000000000000000000003ae0000029d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
|
@ -249,4 +312,4 @@ Window Geometry:
|
|||
collapsed: false
|
||||
Width: 1389
|
||||
X: 472
|
||||
Y: 233
|
||||
Y: 122
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
|
@ -17,13 +17,13 @@
|
|||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
<color rgba="0.8705882352941177 0.8117647058823529 0.7647058823529411 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
|
@ -279,6 +279,8 @@
|
|||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<!-- 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"/>
|
||||
|
@ -322,9 +324,9 @@
|
|||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.008465 0.004045 -0.000763"/>
|
||||
<mass value="9.041"/>
|
||||
<inertia ixx="0.033260231" ixy="-0.000451628" ixz="0.000487603" iyy="0.16117211" iyz="4.8356e-05" izz="0.17460442"/>
|
||||
<origin rpy="0 0 0" xyz="0.008987 0.002243 0.003013"/>
|
||||
<mass value="25"/>
|
||||
<inertia ixx="0.183142146" ixy="-0.001379002" ixz="-0.027956055" iyy="0.756327752" iyz="0.000193774" izz="0.783777558"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
|
@ -358,49 +360,65 @@
|
|||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-0.75" upper="0.75" velocity="20"/>
|
||||
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
|
||||
</joint>
|
||||
<joint name="FR_hip_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.1955 -0.072 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip_rotor"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.12675 0"/>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.09"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.022191 -0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
|
||||
<origin rpy="0 0 0" xyz="-0.020298 -0.009758 0.000109"/>
|
||||
<mass value="2.1"/>
|
||||
<inertia ixx="0.00406608" ixy="0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="FR_thigh_joint" type="continuous">
|
||||
<link name="FR_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.199"/>
|
||||
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.12675 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-1.0" upper="3.5" velocity="20"/>
|
||||
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
|
||||
</joint>
|
||||
<joint name="FR_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 -0.00935 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh_rotor"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
|
@ -411,15 +429,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.05 0.08"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
|
||||
<origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/>
|
||||
<mass value="3.934"/>
|
||||
<inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="FR_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
|
@ -428,7 +466,12 @@
|
|||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-2.6" upper="-0.6" velocity="20"/>
|
||||
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
|
||||
</joint>
|
||||
<joint name="FR_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0519 0"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf_rotor"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
|
@ -439,15 +482,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.04 0.03"/>
|
||||
<box size="0.35 0.04 0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
|
||||
<mass value="0.857"/>
|
||||
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="FR_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
|
@ -470,8 +533,8 @@
|
|||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="3.84e-05" ixy="0.0" ixz="0.0" iyy="3.84e-05" iyz="0.0" izz="3.84e-05"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
|
@ -510,7 +573,12 @@
|
|||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-0.75" upper="0.75" velocity="20"/>
|
||||
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
|
||||
</joint>
|
||||
<joint name="FL_hip_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.1955 0.072 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip_rotor"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
|
@ -521,38 +589,49 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.12675 0"/>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.09"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.022191 0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
|
||||
<origin rpy="0 0 0" xyz="-0.020298 0.009758 0.000109"/>
|
||||
<mass value="2.1"/>
|
||||
<inertia ixx="0.00406608" ixy="-0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="FL_thigh_joint" type="continuous">
|
||||
<link name="FL_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.199"/>
|
||||
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.12675 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-1.0" upper="3.5" velocity="20"/>
|
||||
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
|
||||
</joint>
|
||||
<joint name="FL_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 0.00935 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh_rotor"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
|
@ -563,15 +642,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.05 0.08"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
|
||||
<origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/>
|
||||
<mass value="3.934"/>
|
||||
<inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="FL_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
|
@ -580,7 +679,12 @@
|
|||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-2.6" upper="-0.6" velocity="20"/>
|
||||
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
|
||||
</joint>
|
||||
<joint name="FL_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 -0.0519 0"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf_rotor"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
|
@ -591,15 +695,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.04 0.03"/>
|
||||
<box size="0.35 0.04 0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
|
||||
<mass value="0.857"/>
|
||||
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="FL_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
|
@ -622,8 +746,8 @@
|
|||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="3.84e-05" ixy="0.0" ixz="0.0" iyy="3.84e-05" iyz="0.0" izz="3.84e-05"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
|
@ -662,49 +786,65 @@
|
|||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-0.75" upper="0.75" velocity="20"/>
|
||||
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
|
||||
</joint>
|
||||
<joint name="RR_hip_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="-0.1955 -0.072 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip_rotor"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.12675 0"/>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.09"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.022191 -0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
|
||||
<origin rpy="0 0 0" xyz="0.020298 -0.009758 0.000109"/>
|
||||
<mass value="2.1"/>
|
||||
<inertia ixx="0.00406608" ixy="-0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="RR_thigh_joint" type="continuous">
|
||||
<link name="RR_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.199"/>
|
||||
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.12675 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-1.0" upper="3.5" velocity="20"/>
|
||||
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
|
||||
</joint>
|
||||
<joint name="RR_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 -0.00935 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh_rotor"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
|
@ -715,15 +855,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.05 0.08"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
|
||||
<origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/>
|
||||
<mass value="3.934"/>
|
||||
<inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="RR_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
|
@ -732,7 +892,12 @@
|
|||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-2.6" upper="-0.6" velocity="20"/>
|
||||
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
|
||||
</joint>
|
||||
<joint name="RR_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0519 0"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf_rotor"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
|
@ -743,15 +908,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.04 0.03"/>
|
||||
<box size="0.35 0.04 0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
|
||||
<mass value="0.857"/>
|
||||
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="RR_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
|
@ -774,8 +959,8 @@
|
|||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="3.84e-05" ixy="0.0" ixz="0.0" iyy="3.84e-05" iyz="0.0" izz="3.84e-05"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
|
@ -814,49 +999,65 @@
|
|||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-0.75" upper="0.75" velocity="20"/>
|
||||
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
|
||||
</joint>
|
||||
<joint name="RL_hip_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="-0.1955 0.072 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip_rotor"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.12675 0"/>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.09"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.022191 0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
|
||||
<origin rpy="0 0 0" xyz="0.020298 0.009758 0.000109"/>
|
||||
<mass value="2.1"/>
|
||||
<inertia ixx="0.00406608" ixy="0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="RL_thigh_joint" type="continuous">
|
||||
<link name="RL_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.199"/>
|
||||
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.12675 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-1.0" upper="3.5" velocity="20"/>
|
||||
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
|
||||
</joint>
|
||||
<joint name="RL_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 0.00935 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh_rotor"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
|
@ -867,15 +1068,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.05 0.08"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
|
||||
<origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/>
|
||||
<mass value="3.934"/>
|
||||
<inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="RL_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
|
@ -884,7 +1105,12 @@
|
|||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100" lower="-2.6" upper="-0.6" velocity="20"/>
|
||||
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
|
||||
</joint>
|
||||
<joint name="RL_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.0 -0.0519 0"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf_rotor"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
|
@ -895,15 +1121,35 @@
|
|||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.175"/>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
|
||||
<geometry>
|
||||
<box size="0.35 0.04 0.03"/>
|
||||
<box size="0.35 0.04 0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
|
||||
<mass value="0.857"/>
|
||||
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="RL_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<mass value="0.266"/>
|
||||
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
|
@ -926,8 +1172,8 @@
|
|||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="3.84e-05" ixy="0.0" ixz="0.0" iyy="3.84e-05" iyz="0.0" izz="3.84e-05"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
|
|
|
@ -66,11 +66,11 @@
|
|||
<xacro:property name="thigh_position_max" value="3.5"/>
|
||||
<xacro:property name="thigh_position_min" value="-1.0"/>
|
||||
<xacro:property name="thigh_velocity_max" value="23.32"/>
|
||||
<xacro:property name="thigh_torque_max" value="138.672"/>
|
||||
<xacro:property name="thigh_torque_max" value="93.33"/>
|
||||
<xacro:property name="calf_position_max" value="-0.6"/>
|
||||
<xacro:property name="calf_position_min" value="-2.6"/>
|
||||
<xacro:property name="calf_velocity_max" value="15.55"/>
|
||||
<xacro:property name="calf_torque_max" value="208"/>
|
||||
<xacro:property name="calf_torque_max" value="140"/>
|
||||
|
||||
<!-- dynamics inertial value -->
|
||||
<!-- trunk -->
|
||||
|
|
|
@ -4,10 +4,21 @@
|
|||
|
||||
<xacro:include filename="$(find b1_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae *origin">
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
|
||||
|
||||
<joint name="${name}_hip_joint" type="revolute">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
|
@ -20,6 +31,23 @@
|
|||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_hip_rotor_joint" type="fixed">
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
|
@ -55,21 +83,29 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<link name="${name}_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
|
||||
<mass value="${hip_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
|
||||
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
|
||||
izz="${hip_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
|
@ -80,6 +116,12 @@
|
|||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}" upper="${thigh_position_max}"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -109,6 +151,30 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="${name}_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
|
||||
<mass value="${thigh_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
|
||||
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
|
||||
izz="${thigh_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
|
@ -118,6 +184,12 @@
|
|||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}" upper="${calf_position_max}"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -142,6 +214,30 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="${name}_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
|
||||
<mass value="${calf_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
|
||||
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
|
||||
izz="${calf_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
|
|
|
@ -7,8 +7,8 @@
|
|||
<xacro:include filename="$(find b1_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find b1_description)/xacro/gazebo.xacro"/>
|
||||
|
||||
<!-- Rollover Protection mode will add an additional stick on the top, use "true" or "false" to switch it. -->
|
||||
<xacro:property name="rolloverProtection" value="false"/>
|
||||
<!-- 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)">
|
||||
|
@ -65,37 +65,6 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${(rolloverProtection == 'true')}">
|
||||
<joint name="stick_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="stick_link"/>
|
||||
<origin rpy="0 0 0" xyz="${0.18} 0 ${stick_length/2.0+0.08}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stick_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${stick_mass}"/>
|
||||
<inertia
|
||||
ixx="${stick_mass / 2.0 * (stick_radius*stick_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}" iyz="0.0"
|
||||
izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
|
@ -123,21 +92,10 @@
|
|||
</collision>
|
||||
</link>
|
||||
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False" />
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
|
||||
|
|
Loading…
Reference in New Issue