Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
T
talos-data
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Guilhem Saurel
talos-data
Commits
35901f01
Commit
35901f01
authored
8 years ago
by
Hilario Tome
Browse files
Options
Downloads
Patches
Plain Diff
Added tor leg v2
parent
d59729ca
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
tor_description/robots/tor_lower_body.urdf.xacro
+20
-12
20 additions, 12 deletions
tor_description/robots/tor_lower_body.urdf.xacro
tor_description/urdf/leg/leg_v2.urdf.xacro
+11
-9
11 additions, 9 deletions
tor_description/urdf/leg/leg_v2.urdf.xacro
with
31 additions
and
21 deletions
tor_description/robots/tor_lower_body.urdf.xacro
+
20
−
12
View file @
35901f01
...
@@ -13,31 +13,31 @@
...
@@ -13,31 +13,31 @@
xmlns:controller=
"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:controller=
"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface=
"http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
>
xmlns:interface=
"http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
>
<xacro:include
filename=
"$(find tor_description)/urdf/leg/leg_v2.urdf.xacro"
/>
<xacro:include
filename=
"$(find tor_description)/urdf/leg/leg.urdf.xacro"
/>
<link
name=
"base_link"
>
<link
name=
"base_link"
>
<inertial>
<inertial>
<origin
xyz=
"-0.06071 0.00861 0.06368"
rpy=
"0.00000 0.00000 0.00000"
/>
<origin
xyz=
"0.0 0.0 0.36"
rpy=
"0 0 0"
/>
<mass
value=
"13.34865"
/>
<mass
value=
"34.0"
/>
<inertia
ixx=
"0.06652900000"
ixy=
"-0.00035700000"
ixz=
"0.00027600000"
<inertia
ixx=
"0.529688470"
ixy=
"0.0"
ixz=
"0.0"
iyy=
"0.34860507904"
iyz=
"0.0"
izz=
"0.23865908621"
/>
iyy=
"0.03746500000"
iyz=
"-0.00125400000"
izz=
"0.07895100000"
/>
</inertial>
</inertial>
<visual>
<visual>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<geometry>
<geometry>
<mesh
filename=
"package://tor_description/meshes/
v2/base_link_lo_res
.stl"
scale=
"1 1 1"
/>
<mesh
filename=
"package://tor_description/meshes/
torso_dummy
.stl"
scale=
"1 1 1"
/>
</geometry>
</geometry>
<material
name=
"DarkGrey"
/>
</visual>
</visual>
<collision>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0
.05
"
/>
<geometry>
<geometry>
<mesh
filename=
"package://tor_description/meshes/v2/base_link_collision.stl"
scale=
"1 1
1"
/>
<box
size=
"0.1 0.3 0.
1"
/>
</geometry>
</geometry>
</collision>
</collision>
</link>
</link>
<xacro:tor_leg
prefix=
"left"
reflect=
"1"
/>
<xacro:tor_leg
prefix=
"left"
reflect=
"1"
/>
...
@@ -47,5 +47,13 @@
...
@@ -47,5 +47,13 @@
<xacro:include
filename=
"$(find tor_description)/gazebo/gazebo.urdf.xacro"
/>
<xacro:include
filename=
"$(find tor_description)/gazebo/gazebo.urdf.xacro"
/>
<!-- Materials for visualization -->
<!-- Materials for visualization -->
<xacro:include
filename=
"$(find tor_description)/urdf/materials.urdf.xacro"
/>
<xacro:include
filename=
"$(find tor_description)/urdf/materials.urdf.xacro"
/>
<xacro:include
filename=
"$(find tor_description)/urdf/sensors/imu.urdf.xacro"
/>
<!-- imu -->
<xacro:tor_imu
name=
"imu"
parent=
"base_link"
update_rate=
"100.0"
>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
</xacro:tor_imu>
</robot>
</robot>
This diff is collapsed.
Click to expand it.
tor_description/urdf/leg/leg_v2.urdf.xacro
+
11
−
9
View file @
35901f01
...
@@ -46,10 +46,12 @@
...
@@ -46,10 +46,12 @@
<origin
xyz=
"0.00000 ${reflect*0.08500} -0.14200"
<origin
xyz=
"0.00000 ${reflect*0.08500} -0.14200"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"0 0 1"
/>
<axis
xyz=
"0 0 1"
/>
<!-- trick to use reflect (left=1, right=-1)
<xacro:if
value=
"${reflect == 1}"
>
to make ranges -30 to 90 and -90 to 30 respectively
<limit
lower=
"-0.5236"
upper=
"1.571"
effort=
"100"
velocity=
"3.87"
/>
as (reflect-1.0) will be either 0.0 or -2.0 -->
</xacro:if>
<limit
lower=
"${(-30.0 + (reflect-1.0)*30.0) * deg_to_rad}"
upper=
"${(90.0 + (reflect-1.0)*30.0) * deg_to_rad}"
effort=
"160"
velocity=
"5.8"
/>
<xacro:if
value=
"${reflect == -1}"
>
<limit
lower=
"-1.571"
upper=
"0.5236"
effort=
"100"
velocity=
"3.87"
/>
</xacro:if>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
@@ -87,7 +89,7 @@
...
@@ -87,7 +89,7 @@
<origin
xyz=
"0.00000 0.00000 0.00000"
<origin
xyz=
"0.00000 0.00000 0.00000"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"1 0 0"
/>
<axis
xyz=
"1 0 0"
/>
<limit
lower=
"
${reflect*-30.00000 * deg_to_rad}"
upper=
"${reflect*30.00000 * deg_to_rad}
"
effort=
"160"
velocity=
"5.8"
/>
<limit
lower=
"
-0.524"
upper=
"0.5236
"
effort=
"160"
velocity=
"5.8"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
@@ -124,7 +126,7 @@
...
@@ -124,7 +126,7 @@
<origin
xyz=
"0.00000 0.00000 0.00000"
<origin
xyz=
"0.00000 0.00000 0.00000"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"0 1 0"
/>
<axis
xyz=
"0 1 0"
/>
<limit
lower=
"
${-120.00000 * deg_to_rad}"
upper=
"${45.00000 * deg_to_rad}
"
effort=
"160"
velocity=
"5.8"
/>
<limit
lower=
"
-2.095"
upper=
"0.7
"
effort=
"160"
velocity=
"5.8"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
@@ -162,7 +164,7 @@
...
@@ -162,7 +164,7 @@
<origin
xyz=
"0.00000 0.00000 -0.38000"
<origin
xyz=
"0.00000 0.00000 -0.38000"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"0 1 0"
/>
<axis
xyz=
"0 1 0"
/>
<limit
lower=
"
${0.00000 * deg_to_rad}"
upper=
"${150.00000 * deg_to_rad}
"
effort=
"300"
velocity=
"7"
/>
<limit
lower=
"
0"
upper=
"2.618
"
effort=
"300"
velocity=
"7"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
@@ -199,7 +201,7 @@
...
@@ -199,7 +201,7 @@
<origin
xyz=
"0.00000 0.00000 -0.32500"
<origin
xyz=
"0.00000 0.00000 -0.32500"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"0 1 0"
/>
<axis
xyz=
"0 1 0"
/>
<limit
lower=
"
${-75.00000 * deg_to_rad}"
upper=
"${45.00000 * deg_to_rad}
"
effort=
"160"
velocity=
"5.8"
/>
<limit
lower=
"
-1.309"
upper=
"0.768
"
effort=
"160"
velocity=
"5.8"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
@@ -236,7 +238,7 @@
...
@@ -236,7 +238,7 @@
<origin
xyz=
"0.00000 0.00000 0.00000"
<origin
xyz=
"0.00000 0.00000 0.00000"
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
rpy=
"${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"
/>
<axis
xyz=
"1 0 0"
/>
<axis
xyz=
"1 0 0"
/>
<limit
lower=
"
${-30.00000 * deg_to_rad}"
upper=
"${30.00000 * deg_to_rad}
"
effort=
"100"
velocity=
"4.8"
/>
<limit
lower=
"
-0.524"
upper=
"0.524
"
effort=
"100"
velocity=
"4.8"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
<dynamics
friction=
"${leg_friction}"
damping=
"${leg_damping}"
/>
</joint>
</joint>
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment