ATLAS dimensions, DOF locations
Dear all,
Can anyone have the draw of ATLAS links dimensions and DOF distribution and location?
Best!,
Mario
asked 2013-04-08 23:26:31 -0500
This post is a wiki. Anyone with karma >75 is welcome to improve it.
Dear all,
Can anyone have the draw of ATLAS links dimensions and DOF distribution and location?
Best!,
Mario
Atlas is specified via URDF, its documentation with graphical illustrations can be found here.
The Atlas URDF starts out as a xacro macro, as indicated in the header, atlas.urdf.xacro
uses macros defined in included atlas_simple_shapes.urdf
and others to expand into atlas.urdf
at compile time.
Basic idea reiterated here:
A Model
is composed of a collection of rigid-body Link
s and Joint
constraints. The transform between Link
s are defined in corresponding Joint
blocks. So for example, take a look at this Joint
block in atlas_simple_shapes.urdf.xacro
:
<joint name="back_lbz" type="revolute">
<origin xyz="-0.0125 0 0" rpy="0 -0 0" />
<parent link="pelvis" />
<child link="ltorso" />
...
</joint>
Above basically says: The transform from pelvis Link frame
to ltorso Link frame
is defined by a linear translation of (-0.0125, 0, 0)
, followed by Euler rotation of (0, 0, 0)
radians.
A set of c++ URDF data structures are described here and a corresponding parser is in urdfdom.
One way to visualize URDF model is with rviz. Starting with this DRC Tutorial, you can add a TF
object:
which will display Link
frames:
Asked: 2013-04-08 23:26:31 -0500
Seen: 417 times
Last updated: May 30 '13
what is the kinematic parameter under physics tag in gazebo used for?
Atlas failing in Boston Dynamics Controller demo
how to add collision to walking actor.
Model problems using gazebo_ros_link_attacher for certain movements
Can I add constraints to robot motion in Gazebo?
What is the best practice when creating robots from scratch?
Inverse kinematics for Atlas Arm?
How to get model's kinematics equation?
Physics solver parameters and BDI behavior controller
How to get stable foot contacts when a biped robot is standing still?