51. URDF

AGX Dynamics provides a URDF reader that takes a URDF file and returns an AGX Dynamics representation of the model.

51.1. Examples

Below are two simple examples of how to read a URDF model and access one of its joints, both in C++ and Python. Also, instructions for running the URDF Panda ROS2 Python example is described below.

51.1.1. Example C++

Read a URDF model and access one of its joints.

// Absolute path to the URDF file.
agx::String urdfFile = "absolute/path/model_package/description/model.urdf";

// (Optional) Absolute path to the URDF package path pointing to the 'package://'
// part of any filename attribute in the URDF file if existing.
agx::String urdfPackagePath = "absolute/path/model_package";

// (Optional) Initial joint positions. Must match in length the total number of
// revolute, continous and prismatic joints in the model.
agx::RealVector initJointPos {agx::PI/2.0, -agx::PI/4.0, 0.0, 0.0, 0.0, 0.0};

// (Optional) Determines if the base link of the URDF model should be attached to the
// world or not.
bool attachToWorld = true;

// (Optional) If true (default) the collision between linked/constrained bodies will be disabled.
bool disableLinkedBodies = true;

// Read the URDF.
agxSDK::AssemblyRef model =
  agxModel::UrdfReader::read(urdfFile, urdfPackagePath, &initJointPos, attachToWorld, disableLinkedBodies);

// Add the model to the agxSDK::Simulation.
simulation->add(model);

// Access one of the joints in the model and set wanted speed for it. The name of the constraint
// corresponds to the name of the joint in the URDF file.
agx::Constraint1DOF* joint1 = model->getConstraint1DOF("joint_name");
joint1->getMotor1D()->setEnable(true);
joint1->getMotor1D()->setSpeed(0.5);

51.1.2. Example Python

Read a URDF model and access one of its joints.

# Absolute path to the URDF file.
urdfFile = "absolute/path/model_package/description/model.urdf"

# (Optional) Absolute path to the URDF package path pointing to the 'package://'
# part of any filename attribute in the URDF file if existing.
urdfPackagePath = "absolute/path/model_package"

# (Optional) Initial joint positions. Must match in length the total number of
# revolute, continous and prismatic joints in the model.
initJointPos = agx.RealVector()
initJointPos.append(agx.PI/2.0)
initJointPos.append(-agx.PI/4.0)
for i in range(0, 4):
  initJointPos.append(0.0)

# (Optional) Determines if the base link of the URDF model should be attached to the
# world or not.
attachToWorld = True

# (Optional) If true (default) the collision between linked/constrained bodies will be disabled.
disableLinkedBodies = True


# Read the URDF.
model = agxModel.UrdfReader.read(urdfFile, urdfPackagePath, initJointPos, attachToWorld)

# Add the model to the agxSDK::Simulation. Notice the .get() which is needed since model
# is an agxSDK::AssemblyRef.
sim.add(model.get())

# Access one of the joints in the model and set wanted speed for it. The name of the constraint
# corresponds to the name of the joint in the URDF file.
joint1 = model.getConstraint1DOF("joint_name")
joint1.getMotor1D().setEnable(True)
joint1.getMotor1D().setSpeed(0.5)

51.1.3. Example URDF Panda ROS2

To run this example, ROS2 must be installed. See section Section 43.6 for instructions of how to install and set up ROS2.

Start the URDF Panda robot simulation

  1. Open a new “AGX Dynamics Command Line”.

  2. Call the ROS2 local_setup.bat to setup the ROS2 environment variables. Depending on if you are using the embedded python that comes with AGX Dynamics, or the system installed one, the path to the ros2 library might be different. By default the local_setup.bat is located in your ros2-algoryx installation directory, eg:

Algoryx/AGX-version/python-x64/site-packages/ros2-algoryx/ros2/local_setup.bat
  1. In the AGX command prompt, cd to the AGX ROS2 examples directory, e.g:

cd Algoryx/AGX-version/data/python/ROS2
  1. Run the URDF Panda ROS2 script by calling python, i.e:

python urdf_panda_ros2.py

Start the URDF Panda ROS2 controller

  1. Follow steps 1-3 from above.

  2. Run the URDF Panda ROS2 controller script by calling python, i.e:

python urdf_panda_ros2_controller.py

51.2. Supported features overview

Below is an overview of the URDF features. Those marked with ‘✓’ are supported by the URDF reader and those marked with ‘☓’ are not.

robot ✓
│   name ✓
│
└───link ✓
│   │   name ✓
│   │
│   └───inertial ✓
│   │   │
│   │   └───origin ✓
│   │   │      xyz ✓
│   │   │      rpy ✓
│   │   │
│   │   └───mass ✓
│   │   │      value ✓
│   │   │
│   │   └───intertia ✓
│   │          ixx - izz ✓
│   │
│   └───visual ✓
│   │   │   name ✓
│   │   │
│   │   └───origin ✓
│   │   │      xyz ✓
│   │   │      rpy ✓
│   │   │
│   │   └───geometry ✓
│   │   │   │
│   │   │   └───box ✓
│   │   │   │      size ✓
│   │   │   │
│   │   │   └───cylinder ✓
│   │   │   │      radius ✓
│   │   │   │      length ✓
│   │   │   │
│   │   │   └───sphere ✓
│   │   │   │      radius ✓
│   │   │   │
│   │   │   └───mesh ✓
│   │   │          filename ✓
│   │   │          scale ✓
│   │   │
│   │   └───material ✓
│   │       │   name ✓
│   │       │
│   │       └───color ✓
│   │       │      rgba ✓
│   │       │
│   │       └───texture ✓
│   │
│   └───collision ✓
│       │   name ✓
│       │
│       └───origin ✓
│       │      xyz ✓
│       │      rpy ✓
│       │
│       └───geometry ✓
│              (see geometry under 'visual' above)
│
└───joint ✓
│   │   name ✓
│   │   type: revolute ✓
│   │   type: continuous ✓
│   │   type: prismatic ✓
│   │   type: fixed ✓
│   │   type: floating ✓
│   │   type: planar ✓
│   │
│   └───parent ✓
│   │      link ✓
│   │
│   └───child ✓
│   │      link ✓
│   │
│   └───axis ✓
│   │      xyz ✓
│   │
│   └───calibration ☓
│   │
│   └───dynamics ✓
│   │      damping ☓
│   │      friction ✓
│   │
│   └───limit ✓
│   │      lower ✓
│   │      upper ✓
│   │      effort ✓
│   │      velocity ☓
│   │
│   └───mimic ✓
│   │      multiplier ✓
│   │      offset ✓
│   │
│   └───safety_controller ☓
│
└───transmission ☓
│
└───gazebo ☓
│
└───sensor ☓
│
└───model_state ☓

51.3. AGX Dynamics representation

Below is a detailed description of the how the URDF features are represented by AGX Dynamics.

51.3.1. <robot>

The root element robot is represented by an agxSDK::Assembly. The name of the agxSDK::Assembly is set to the required name attribute.

51.3.3. <joint>

Each joint element is represented by an agx::Constraint. The name of the agx::Constraint is set to the required name attribute. Any revolute joint is represented by an agx::Hinge with the secondary constraint agx::RangeController active. Any continuous joint is represented by an agx::Hinge. Any prismatic joint is represented by an agx::Prismatic with the secondary constraint agx::RangeController active. Any fixed joint is represented by an agx::LockJoint. Any floating joint is ignored since free body movement is the default behaviour of any agx::RigidBody. Any planar joint is represented by an agx::PlaneJoint.

51.3.3.1. <origin>

The optional origin element specifies the position and orientation of the child agx::RigidBody representing the child link with respect to the parent agx::RigidBody representing the parent link. If not specified identity position and orientation is used.

51.3.3.2. <parent>

The required link attribute of the required parent element specifies the name of the parent agx::RigidBody that is attached to the agx::Constraint representing the joint.

51.3.3.3. <child>

The required link attribute of the required child element specifies the name of the child agx::RigidBody that is attached to the agx::Constraint representing the joint.

51.3.3.4. <axis>

The optional axis element determines the axis of rotation for any agx::Hinge representing a revolute or continuous joint, or the axis of translation for any agx::Prismatic representing a prismatic joint. If not specified, then [1, 0, 0] is used.

51.3.3.5. <calibration>

Not supported and will be ignored.

51.3.3.6. <dynamics>

The optional dynamics element determines the dynamic behaviour of the agx::Constraint representing a joint. If not specified the default AGX Dynamics parameters are used for the agx::Constraint.

51.3.3.6.1. damping

Not supported and will be ignored. Note that it is possible to manually set the damping for any DOF for a agx::Constraint representing a joint. This can be done by accessing the agx::Constraint from the returned agxSDK::Assembly followed by calling the function agx::Constraint::setDamping(…).

51.3.3.6.2. friction

The optional friction attribute specifies the static friction of the joint in Newtons. This corresponds to a force range of the secondary constraint agx::FrictionController of the agx::Constraint and is applied as such. If the friction attribute is not specified, the default AGX Dynamics friction is used.

51.3.3.7. <limit>

The limit element specifies the upper and lower bounds of of the joint both in terms of rotational/translational freedom and in maximal force/torque. The limit element is supported only for revolute and prismatic joint’s and for those it is also a required element.

The lower and upper attributes are represented as the lower and upper range of the secondary constraint agx::RangeController and are applied as such. If not specified, then 0 is used for both attributes. The required effort attribute specifies the maximum force/torque of the agx::Constraint’s secondary constraints: agx::RangeController, agx::LockController and agx::TargetSpeedController. The velocity attribute is not supported and will be ignored.

51.3.3.8. <mimic>

The optional mimic element makes it possible to configure an agx::Constraint representing the joint in such a way that it will move in accordance with another agx::Constraint. Internally any mimic element is represented as a agxPowerLine::PowerLine with a number of agxPowerLine::Connector’s together with an agxDriveTrain::Gear configured to give this behaviour. The mimic feature is supported for revolute, continuous and prismatic joint’s. Having a revolute or continuous joint mimic a prismatic joint or vice versa is not supported, but having a revolute joint mimic a continuous joint or vice versa is.

51.3.3.8.1. multiplier

The optional multiplier attribute corresponds to a gear ratio of the agxDriveTrain::Gear that is part of the agxPowerLine::PowerLine representing the mimic element. If not specified the value 1 is used.

51.3.3.8.2. offset

The optional offset attribute will add an initial rotational or translational offset to the agx::Constraint representing the joint with the mimic element. If an initial joint value is set using the joints parameter when calling the agxModel::UrdfReader::read() function, the offset attribute will be added to this initial joint value.

51.3.3.9. <safety_controller>

Not supported and will be ignored.

51.3.4. <transmission>

Not supported and will be ignored.

51.3.5. <gazebo>

Not supported and will be ignored.

51.3.6. <sensor>

Not supported and will be ignored.

51.3.7. <model_state>

Not supported and will be ignored.