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
Stack Of Tasks
talos-data
Commits
ca2f97de
Commit
ca2f97de
authored
8 years ago
by
Luca Marchionni
Browse files
Options
Downloads
Patches
Plain Diff
Invert torso joints order. Check base_link
parent
afa97cfc
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
talos_description/urdf/torso/torso.urdf.xacro
+10
-10
10 additions, 10 deletions
talos_description/urdf/torso/torso.urdf.xacro
with
10 additions
and
10 deletions
talos_description/urdf/torso/torso.urdf.xacro
+
10
−
10
View file @
ca2f97de
...
@@ -77,13 +77,13 @@
...
@@ -77,13 +77,13 @@
</link>
</link>
<joint
name=
"${name}_1_joint"
type=
"revolute"
>
<joint
name=
"${name}_1_joint"
type=
"revolute"
>
<parent
link=
"
${name}_2
_link"
/>
<parent
link=
"
base
_link"
/>
<child
link=
"${name}_1_link"
/>
<child
link=
"${name}_1_link"
/>
<origin
xyz=
"0.0 0.0 0.0"
<origin
xyz=
"0.0 0.0 0.0
722
"
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
0 1
"
/>
<limit
lower=
"${-
4
5.0 * deg_to_rad}"
upper=
"${
1
5.0 * deg_to_rad}"
<limit
lower=
"${-
7
5.0
0000
* deg_to_rad}"
upper=
"${
7
5.0
0000
* deg_to_rad}"
effort=
"${torso_max_effort}"
velocity=
"${torso_max_vel}"
/>
effort=
"${torso_max_effort}"
velocity=
"${torso_max_vel}"
/>
<dynamics
damping=
"1.0"
friction=
"1.0"
/>
<dynamics
damping=
"1.0"
friction=
"1.0"
/>
<!-- <safety_controller k_position="20"
<!-- <safety_controller k_position="20"
...
@@ -122,12 +122,12 @@
...
@@ -122,12 +122,12 @@
<joint
name=
"${name}_2_joint"
type=
"revolute"
>
<joint
name=
"${name}_2_joint"
type=
"revolute"
>
<parent
link=
"${name}_1_link"
/>
<parent
link=
"${name}_1_link"
/>
<child
link=
"
base
_link"
/>
<child
link=
"
${name}_2
_link"
/>
<origin
xyz=
"0.0 0.0
-
0.0
722
"
<origin
xyz=
"0.0 0.0 0.0"
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
1 0
"
/>
<limit
lower=
"${-
7
5.0
0000
* deg_to_rad}"
upper=
"${
7
5.0
0000
* deg_to_rad}"
<limit
lower=
"${-
1
5.0 * deg_to_rad}"
upper=
"${
4
5.0 * deg_to_rad}"
effort=
"${torso_max_effort}"
velocity=
"${torso_max_vel}"
/>
effort=
"${torso_max_effort}"
velocity=
"${torso_max_vel}"
/>
<dynamics
friction=
"1.0"
damping=
"1.0"
/>
<dynamics
friction=
"1.0"
damping=
"1.0"
/>
<!-- <safety_controller k_position="20"
<!-- <safety_controller k_position="20"
...
...
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