OpenRAVE Documentation

  • 0.8.0
  • 0.8.2
  • Documentation version: latest_stable

COLLADA Robot Extensions (Version 0.3.3)

OpenRAVE maintains a set of robot-specific extensions to the COLLADA 1.5 specification in order to exchange data with robotics applications. By default, COLLADA 1.5 handles geometry, visual effects, physical properties, and complex kinematics while the robot-specific extensions include:

  • manipulators
  • sensors
  • collision data - geometries for environment, self-collision, visual info, etc
  • planning-specific parameters

COLLADA allows extensions of any of its tags using the <extra> tag. Each <extra> defines what type of information to provide and a format for that information, also called technique. All custom data defined here uses the OpenRAVE technique.

There are one-to-one correspondences between the OpenRAVE interface types and COLLADA tags:

  • Robot/KinBody <-> articulated_system
  • Sensor <-> sensor
  • Manipulator <-> manipulator

interface_type

Introduction

Specifies the type of kinematics body/robot type to instantiate inside the code.

Concepts

All of the kinematics body methods can be overridden with new implementations. Because this requires loading user code, a user-provided instantiation has to be used. The interface type specifies what this type is and where to load it from.

Child Elements

Element Description Occurances
<interface> Contains the string id of the interface 1
<plugin> Optional. Contains the string of the location of the shared object object to load. Because plugin prefixes and suffixes depends on the OS, a prefix and suffix independent name can be specified. 0 or 1

Attributes for <interface>

type xs:token Required. The type of interface to create: robot, kinbody, sensor, iksolver, etc

Example

<extra type="interface_type">
  <technique profile="OpenRAVE">
    <interface type="robot">MyGenericRobot</interface>
    <plugin>myplugin</plugin>
  </technique>
</extra>

manipulator

Introduction

Defines a subset of the robot that acts as an arm and a gripper.

Concepts

The arm is a chain of joints whose end effector is treated as a gripper. The arm is extracted from the origin and tip links. The tip contains the manipulator frame of reference. The gripper axes have to be specified manually. The direction is used as a hint for grasping and inverse kinematics.

Related Elements

Parent elements <articulated_system>

Child Elements

Element Description Occurances
<frame_origin> The base frame that the arm starts at 1
<frame_tip> The end effector frame the arm ends at 1
<gripper_joint> Defines one joint of the gripper 0 or more
<iksolver> Defines properties of inverse kinematics functions when used with the arm 0 or more

Attributes for <frame_origin>/<frame_tip>

link xs:token Required. References the SID of a <link> defined in <kinematics_model>.

Child Elements for <frame_tip>

Element Description Occurances
<translate> Translation. See main entry in Core. 0 or more
<rotate> Rotation axis. See main entry in Core. 0 or more
<direction> Direction meta information. Sometimes IK and other modules require the manipulator to have a direction to measure angles from. This is defined inside the frame tip coordinate system. 0 or 1

Attributes for <gripper_joint>

joint xs:token Required. The reference of the joint in the instantiated kinematics model that is part of the gripper.

Child Elements for <gripper_joint>

Element Description Occurances
<closing_direction> common_float_or_param_type that contains the default closing direction of an axis on the joint. If a closing direction is not specified for an axis in the joint, it defaults to 0. 0 or more

Attributes for <gripper_joint>/<closing_direction>

axis xs:token Required. The SID of the axis inside the referenced joint.

Attributes for <iksolver>

type xs:token Required. The type of the inverse kinematics to set a property for. Possible types are: Transform6D, Rotation3D, Translation3D, Direction3D, Ray4D, Lookat3D, TranslationDirection5D.

Child Elements for <iksolver>

Element Description Occurances
<free_joint> Specifies one free joint to use for ik. 0 or more
<interface_type> Optional. Specifies the interface of the inverse kinematics solver. 0 or 1

Attributes for <iksolver>/<free_joint>

joint xs:token Required. The reference of the joint in the instantiated kinematics model that is part of the manipulator chain.
stepsize xs:float The discretization value of this joint when searching for solutions

Details

The current IK types are:

  • Transform6D - end effector reaches desired 6D transformation
  • Rotation3D - end effector reaches desired 3D rotation
  • Translation3D - end effector origin reaches desired 3D translation
  • Direction3D - direction on end effector coordinate system reaches desired direction
  • Ray4D - ray on end effector coordinate system reaches desired global ray
  • Lookat3D - direction on end effector coordinate system points to desired 3D position
  • TranslationDirection5D - end effector origin and direction reaches desired 3D translation and direction. Can be thought of as Ray IK where the origin of the ray must coincide.

The IK types are meant to be hints as to how a manipulator can be used. Multiple IK types can be set for one manipulator and differing free joint values. It is possible for a post-processing stage to determine what IK types are best suited for a particular manipulator structure, and then add those into the COLLADA file.

  • Why is a manipulator frame necessary?
    • Answer: Manipulator frames allow the user to define a coordinate system where it makes target tasks easier to complete. In this regard, the manipulator frame can be freely chosen by the user without worrying about destroying the link coordinate systems. For example, link frames are usually aligned with joint axes and center of masses and robot state is defined by their 6D transform in space. Having them also represent task-specific information could destroy consistency when the task changes. Also, the z-axis of the manipulator frame can define the “direction” of the manipulator. Direction can be used in many places like sensor line of sight and grasping approach, which makes it possible to quickly use the robot for planning.
  • Question: For dual arm manipulation, would a leftright manipulator ever be used including all joints? In this case, will it might be necessary to define two frame tips (one for left arm and one for right arm)?
    • Answer: Having a leftright manipulator destroys the one-to-one correspondence between gripper joints and ik solver, and not much is gained. So better to have only have one frame tip and origin and treat two arms as separate. The constraint between the end effectors of the two arms is not always rigid, it very task dependent. Therefore, the user should take care of the dual relation.
  • Question: What about closing gripper direction for complex hands? Fingers with many DOF might need special grasping strategies.
    • Answer: The closing direction just provide a hint as to the usage. The real gripper movement depends on the grasp strategy, which is beyond the definition of this scope.

Example

The example defines an arm with an end effector at link wam7 with a local coordinate system. It also defines two gripper axes. For the ‘transform6d’ inverse kinematics type, it specifies that the free joint should be ‘joint4’.

<articulated_system>
  <extra type="manipulator" name="leftarm">
    <technique profile="OpenRAVE">
      <frame_origin link="wam0"/>
      <frame_tip link="wam7">
        <translate>0.0 0.0 0.22</translate>
        <rotate>0.0 1.0 0.0 90.0</rotate>
        <direction>0.0 0.0 1.0</direction>
      </frame_tip>
      <gripper_joint joint="jointname">
        <closing_direction axis="axis0">
          <float>1</float>
        </closing_direction>
      </gripper_joint>
      <gripper_joint joint="jointname2">
        <closing_direction axis="axis0">
          <float>-1</float>
        </closing_direction>
      </gripper_joint>
      <iksolver type="Transform6D">
        <free_joint joint="jointname3"/>
        <interface_type>
          <technique profile="OpenRAVE">
            <interface>WAM7ikfast</interface>
            <plugin>WAM7ikfast</plugin>
          </technique>
        </interface_type>
      </iksolver>
      <iksolver type="Translation3D">
        <free_joint joint="jointname4"/>
      </iksolver>
    </technique>
  </extra>
</articulated_system>

dynamic_rigid_constraints

Introduction

Defines a list of rigid constraints within pairs of bodies modeling dynamic inter-relationships of physics models like a robot hand grabbing an object.

Concepts

Allows new rigid constraints to be specified that are not associated with physics models, but instead of with the instantiated physics and visual scenes. Common rigid constraints for robotics are:

  • a robot hand grasping an object with its hand.
  • robot grasping a tool, which then grasps the object
  • robot hand grasps a cylindrical pole, so it is free to rotate the hand with respect to the cylinder axis.

Related Elements

Parent elements <instance_physics_scene>

Child Elements

Element Description Occurances
<rigid_constraint> A list of rigid constraints 0 or more
<rigid_constraint>/<technique>/<ignore_link> The sid of a link whose collision is ignored with the attached body. The link belongs to the ref_attachment physics model. 0 or more

Details

Example

Describes robot whose physics model SID is pmodel1_inst grabbing with its rigid_hand link an object whose physics model SID is pmodel2_inst. rigid_hand is the SID of the <instance_rigid_body> inside pmodel1_inst.

<instance_physics_scene url="#pscene">
  <extra type="dynamic_rigid_constraints">
    <technique profile="OpenRAVE">
      <rigid_constraint>
        <ref_attachment rigid_body="pmodel1_inst/rigid_hand"/>
        <attachment rigid_body="pmodel2_inst/rigid0"/>
        <technique profile="OpenRAVE">
          <ignore_link link="pmodel1_inst/rigid_dummy"/>
          <ignore_link link="pmodel1_inst/rigid2"/>
        </technique>
      </rigid_constraint>
    </technique>
  </extra>
</instance_physics_scene>

collision

Introduction

Links all possible collision meshes and properties for one kinematics body. The meshes depends on the usage.

Concepts

A link can have three different collision meshes:

  • for visual rendering
  • for self-collisions
  • for environment collisions

For each link, COLLADA will store three geometries in the <library_geometries>. The geometries will have an <extra> tag that specifies which usage they are meant to. The self and env will be referenced inside the visual geometry.

The tag also stores information about what pairs of links can be completely ignored from self-collision detection. These links are either adjacent to each other, or so far from each other that no configuration of the robot can get them into possible collision.

Related Elements

Parent elements <kinematics_model>, <articulated_system>

Child Elements

Element Description Occurances
<bind_instance_geometry> The geometry used for a particular link 0 or more
<ignore_link_pair> Specifies two links pairs whose self-collision should not be checked 0 or more
<link_collision_state> Contains a common_bool_or_param_type that specifies if a link should be used for collision or not. Can enable or disable it. 0 or more

Attributes for <bind_instance_geometry>

type xs:token Required. The usage type: environment or self
link xs:token Required. References the SID of a <link> defined in <kinematics_model>. This link is where the geometries will be added.
url xs:anyURI Required. The URL of the location of the <geometry> element to instantiate. Can refer to a local instance or external reference.

Details

Convex decompositions can be defined by using one geometry per convex hull and attaching multiple geometries to the same link.

<ignore_link_pair> tags help self-collision detection to help prune possibilities. The adjacency information is not just the neighboring links. It is also meant to prune any collisions between two links that cannot possibly happen if the robot maintains its joint limits. This information depends not only on the kinematics of the robot, but also on the geometry of every link. Also for triplets of joints j1, j2, j3 that intersect at a common axis, you would want to add (j1,j2),(j2,j3),(j1,j3).

By default, all links are colliding unless turned off via <link_collision_state>.

Example

<library_visual_scenes>
  <node id="mynode">
    <instance_geometry url="#linka_vis0"/>
    <instance_geometry url="#linka_vis1"/>
  </node>
</library_visual_scenes>
<library_geometries>
  <geometry id="linka_vis0"/>
  <geometry id="linka_vis1"/>
  <geometry id="linka_env0"/>
  <geometry id="linka_env1"/>
  <geometry id="linka_self"/>
  <geometry id="linkb_env0"/>
</library_geometries>
<library_kinematics_models>
  <kinematics_model>
    <extra type="collision">
      <technique profile="OpenRAVE">
        <bind_instance_geometry type="environment" link="linka" url="#linka_env0"/>
        <bind_instance_geometry type="environment" link="linka" url="#linka_env1"/>
        <bind_instance_geometry type="self" link="linka" url="#linka_self"/>
        <bind_instance_geometry type="environment" link="linkb" url="#linkb_env0"/>
        <ignore_link_pair link0="linka" link1="linkb"/>
        <link_collision_state link="linka"><bool>true</bool></link_collision_state>
      </technique>
    </extra>
</library_kinematics_models>

geometry_info

Introduction

Uses the COLLADA Physics specification of Analytical Shapes to summarize geometric information in simpler terms like box, cylinder, sphere, etc.

Concepts

A simple geometric element like an oriented box can be very difficult to exactly define with triangle meshes or brep presentations. Furthermore, elements like spheres must use brep, which require a deep understanding of the new brep specification. By using the <geometry_info> element, a user can give a hint to the user as to what shape the geometry mesh represents using the physics specifications like <box>.

In order to represent an oriented bounding box, a coordinate system can be defined within <geometry_info> by using the <translate> and <rotate> tags.

Related Elements

Parent elements <geometry>

Child Elements

Element Description Occurances
<visible> Contains a common_bool_or_param_type that specifies whether the geometry is visible or not. 0 or 1
<translate> Translate the simple geometry shape. See main entry in Core. 0 or more
<rotate> Rotation axis for rotating the simple geometry. See main entry in Core. 0 or more
geometry of the shape An inline definition using one of the following COLLADA Physics analytical shape elements: <plane>, <box>, <sphere>, <cylinder>, or <capsule> 0 or 1

Attributes for <parameters>

Details

It is possible to only define the local coordinate system of the geometry without defining an extra analytical shape.

Example

Translation box center to (0,0,0.5) and rotate 45 degrees around z axis.

<geometry>
  <extra type="geometry_info">
    <technique profile="OpenRAVE">
      <box>
        <half_extents>0.1 0.2 0.3</half_extents>
      </box>
      <translate>0 0 0.5</translate>
      <rotate>0 0 1 45</rotate>
      <visible><bool>true</bool></visible>
    </technique>
  </extra>
</geometry>

joint_info

Introduction

Defines extra joint parameters not part of the COLLADA 1.5 specification.

Concepts

The parameters are key/value-array pairs.

Attributes

name xs:token Required. References the SID of a <joint> defined in <kinematics_model>. One of the joints defining the pair to be ignored.

Related Elements

Parent elements <kinematics_model>

Child Elements

Element Description Occurances
<float_array> An array of floating-point values 0 or more
<int_array> An array of floating-point values 0 or more

Example

Sets myparam to joint0 and newparam to joint1.

<kinematics_model>
  <extra type="joint_info" name="joint0">
    <technique profile="OpenRAVE">
      <float_array joint="joint0" name="myparam">1.0 2.0 3.0</float_array>
    </technique>
  </extra>
  <extra type="joint_info" name="joint0">
    <technique profile="OpenRAVE">
      <int_array joint="joint1" name="newparam">-10</int_array>
    </technique>
  </extra>
</kinematics_model>

library_sensors

Introduction

Provides a library in which to place <sensor> elements.

Concepts

Allows sensors to be stored as modular resources in libraries. Can be easily referenced through files.

Related Elements

Parent elements <COLLADA>

sensor

Introduction

Defines a sensor’s type and the geometric and intrinsic parameters.

Concepts

Each sensor will be associated with a particular sensor type; depending on the sensor type, the parameters that need to be set will change. The parameters should contain everything necessary to simulate the sensor accurately. They should not contain parameters that define the format and transfer of the data.

Related Elements

Parent elements <articulated_system>

Attributes

type xs:token Required. The type of the sensor. Possible types are: base_pinhole_camera, base_stereo_camera, base_laser2d, base_laser3d, base_flash_laser, base_encoder, base_force6d, base_imu, base_odometry
id xs:ID Required. A text string containing the unique identifier of the <sensor> element. This value must be unique within the instance document.

Child Elements

common:

Element Description Occurances
<interface_type> Optional. Contains the interface type to load the sensor with. 0 or 1

type base_pinhole_camera:

Simple pin hole camera defined by an intrinsic matrix. The camera can support multiple image dimensions with multiple channel formats. It is not clear whether all supported formats for one camera should be enumerated in one <sensor> tag, or there should be multiple sensor tags for each different type where the sensors are exclusively mutual.

<image_dimensions> Contains a int3_type that specifies the image width, height, and channels. 1
<format> Contains a string that specifies the format of every value in the image. Possible types are uint8, uint16, uint32, int8, int16, int32, float32, float64. 1
<measurement_time> Contains a float_type that specifies time between images (ie exposure time). 0 or 1
<intrinsic> Contains a float2x3_type that specifies the intrinsic parameters defining the principal point, field of view, and skew. 1
<focal_length> Contains a float_type that specifies the physical focal length of the camera. 0 or 1
<distortion_model> The distortion model to use. It has a type attribute specifying the actual model type, and contains a list_of_floats_type that specifies the distortion coefficients of the model. 0 or 1

type base_stereo_camera:

Uses two cameras together to extract a depth map. The stereo camera’s coordinate system is in the first instanced camera.

<instance_sensor> The camera sensors, the scan time should be equal 2

Attributes for <instance_sensor>

url xs:anyURI Required. The URL of the location of the <sensor> element to instantiate.

Child Elements for <instance_sensor>

Element Description Occurances
<rectification> Contains a float3x3_type that specifies a homography which takes an image to the ideal stereo image plane so that epipolar lines in both stereo images are parallel. The homography transforms from the second image to the first image. 1

type base_laser2d:

Single scan from a planar laser range-finder along the xy plane.

<angle_range> Contains a float2_type that specifies the minimum and maximum angles (degrees) of the laser range. 1
<distance_range> Contains a float2_type that specifies the minimum and maximum distance of the laser. 1
<angle_increment> Contains a float_type that specifies the angular distance between measurements (degrees). 1
<time_increment> Contains a float_type that specifies the time between measurements (seconds). If your scanner is moving, this will be used in interpolating position of 3d points. 1
<measurement_time> Contains a float_type that specifies the time between scans (seconds) 1

type base_laser3d:

type base_flash_laser:

type base_encoder:

type base_force6d:

<load_range_force> Contains a float3_type that specifies the maximum force around the XYZ axes the sensor can accurately measure before saturating. Units are Mass * Distance² * Time-². 0 or 1
<load_range_torque> Contains a float3_type that specifies the maximum torque around the XYZ axes the sensor can accurately measure before saturating. Units are Mass * Distance * Time-². 0 or 1
<load_resolution_force> Contains a float3_type that specifies the sensing resolution of the forces being measured around the XYZ axes. Units are Mass * Distance² * Time-². 0 or 1
<load_resolution_torque> Contains a float3_type that specifies the sensing resolution of the torques being measured around the XYZ axes. Units are Mass * Distance² * Time-². 0 or 1
<load_capacity_range_force> Contains a float3_type that specifies the maximum force around the XYZ axes the sensor can withstand before breaking. Units are Mass * Distance² * Time-². 0 or 1
<load_capacity_range_torque> Contains a float3_type that specifies the maximum torque around the XYZ axes the sensor can withstand before breaking. Units are Mass * Distance² * Time-². 0 or 1

type base_imu:

<measurement_time> Contains a float_type that specifies the time between scans (seconds). 1
<rotation_covariance> The uncertainty covariance matrix (3x3 row-major matrix) in x, y, and z axes. 1
<angular_velocity_covariance> The uncertainty covariance matrix (3x3 row-major matrix) in x, y, and z axes. 1
<linear_acceleration_covariance> The uncertainty covariance matrix (3x3 row-major matrix) in x, y, and z axes. 1

type base_odometry:

<measurement_time> Contains a float_type that specifies the time between scans (seconds). 1
<target> The name of the target whose odometry is being measured 0 or 1

Example

Example using a default sensor with a custom interface

<extra type="library_sensors" id="libsensors">
  <technique profile="OpenRAVE">
    <sensor type="base_laser2d" id="ExampleLaser1">
      <angle_min>-90</angle_min>
      <angle_max>90</angle_max>
      <range_min>0.01</range_min>
      <range_max>4.0</range_max>
      <angle_increment>1</angle_increment>
      <time_increment>0.0005</time_increment>
      <measurement_time>0.025</measurement_time>
      <interface_type>
        <technique profile="OpenRAVE">
          <interface>BaseLaser2D</interface>
        </technique>
      </interface_type>
    </sensor>
  </technique>
</extra>

Using a non-default, custom sensor

<extra type="library_sensors" id="libsensors">
  <technique profile="OpenRAVE">
    <sensor type="BaseLaser2D" id="ExampleLaser1">
      <minangle>-135</minangle>
      <maxangle>135</maxangle>
      <resolution>0.35</resolution>
      <maxrange>5</maxrange>
      <scantime>0.1</scantime>
      <color>0.5 0.5 1</color>
    </sensor>
  </technique>
</extra>

Develop a formal sensor XML file format for different sensor types.

attach_sensor

Introduction

Attaches a sensor to a link of the robot.

Concepts

The sensor comes from the sensor library. It can be attached anywhere onto a link defined from the kinematics section. The sensor will maintain a constant transformation between the link.

Related Elements

Parent elements <articulated_system>

Child Elements

Element Description Occurances
<instance_sensor> Instantiate a sensor. 1
<frame_origin> The base link that the sensor is attached to. 1

Attributes for <frame_origin>

link xs:token Required. References the SID of a <link> defined in <kinematics_model>.

Child Elements for <frame_origin>

Element Description Occurances
<translate> Translation. See main entry in Core. 0 or more
<rotate> Rotation axis. See main entry in Core. 0 or more

Example

<extra type="attach_sensor" name="left_head_camera">
  <technique profile="OpenRAVE">
    <instance_sensor url="#pgr_camera"/>
    <frame_origin link="head">
      <translate>0 1 0</translate>
      <rotate>0 1 0 90</rotate>
    </frame_origin>
  </technique>
</extra>

formula/technique

Introduction

Full specifies a formula for a joint and annotates it with extra information necessary for robotics.

Concepts

The original <formula>/<technique_common> supports only one equation for the value of the joint. More complex kinematics systems have more than one degree of freedom per joint and use the partial derivatives of the equation to compute Jacobians and simulate physics.

This “OpenRAVE” technique for <formula> can specify partial derivatives of the position equation for computing velocity and accelerations.

Related Elements

Parent elements <formula>

Child Elements

Element Description Occurances
<equation> Equation in MathML format. Used to specify the position and partial derivatives. 0 or more

Attributes for <equation>

type xs:token Required. can be one of “position”, “first_partial”, or “second_partial”.
target xs:token If ‘type’ is “first_partial” or “second_partial”, then fill this with the variable taking the partial derivative with respect to.

Example

<technique profile="OpenRAVE">
  <equation type="position">
    <math>
      <apply>
        <plus/>
        <apply>
          <times/>
          <cn>0.333330</cn>
          <csymbol encoding="COLLADA">kmodel1/joint0</csymbol>
        </apply>
        <cn>0.872700</cn>
      </apply>
    </math>
  </equation>
  <equation type="first_partial" target="kmodel1/joint0">
    <math>
      <cn>0.333330</cn>
    </math>
  </equation>
</technique>

library_actuators

Introduction

Provides a library in which to place <actuator> elements.

Concepts

Allows actuators to be stored as modular resources in libraries. Can be easily referenced through files.

Related Elements

Parent elements <COLLADA>

actuator

Introduction

An actuator provides force/momentum/action to kinematics joints.

Concepts

Defines a actuator’s physical properties necessary to simulate dynamics and control algorithms of a robot. They should not contain parameters that define the format and transfer of the data to and from actuators.

Related Elements

Parent elements <articulated_system>

Attributes

type xs:token Required. The type of the actuator. Possible types are: motor
id xs:ID Required. A text string containing the unique identifier of the <actuator> element. This value must be unique within the instance document.

Child Elements

common:

Element Description Occurances
<interface_type> Optional. Contains the interface type to load the actuator with. 0 or 1

type electric_motor:

Converts electrical energy into mechanical energy usually using magnetic fields and conductors. The speed of a motor is measured in revolutions/Time (Time is defined by the <asset> tag and usually measured in seconds). DC Motor Theory References:

<assigned_power_rating> Contains a float_type that specifies the nominal power the electric motor can safely produce. Units are Mass * Distance² * Time-³. 1
<max_speed> Contains a float_type that specifies the maximum speed of the motor. Units are Time-¹. 1
<no_load_speed> Contains a float_type that specifies the speed of the motor powered by the nominal voltage when the motor provides zero torque. Units are Time-¹. 0 or 1
<nominal_torque> Contains a float_type that specifies the maximum torque the motor can provide continuously without overheating. Units are Mass * Distance * Time-². 1
<nominal_voltage> Contains a float_type that specifies the nominal voltage the electric motor can safely produce. Units are Mass * Distance² * Time-² * Charge. 1
<rotor_inertia> Contains a float_type that specifies the inertia of the rotating element about the axis of rotation. Units are Mass * Distance². 1
<speed_constant> Contains a float_type that specifies the constant of proportionality relating speed to voltage. Units are Mass-¹ * Distance-² * Time * Charge-¹. 1
<speed_torque_gradient> Contains a float_type that specifies the slope of the speed-torque curve, approximately equal to the no load speed divided by the stall torque. Units are ** Mass-¹ * Distance-¹ * Time-¹**. 1
<starting_current> Contains a float_type that specifies the current through the motor at zero velocity, equal to the nominal voltage divided by the terminal resistance. Also called the stall current. Units are Time-¹ * Charge. 1
<terminal_resistance> Contains a float_type that specifies the resistance of the motor windings. Units are Mass * Distance² * Time-¹ * Charge-². 1
<torque_constant> Contains a float_type that specifies the proportion relating current to torque. Units are Mass * Distance * Time-¹ * Charge-¹. 1
<gear_ratio> Contains a float type that specifies the ratio between the input speed of the transmission (the speed of the motor shaft) and the output speed of the transmission.  

Related variables, but not inserted in the electric_motor specification:

  • Stall torque - The time it takes the unloaded motor to reach 63% of its no load speed under a constant voltage, starting from rest. Proportional to the inertia of the rotor and inversely proportional to the square of the the torque constant.
  • Max. efficiency - The maximum efficiency of the motor in converting electrical power to mechanical power. This maximum efficiency typically occurs at high speed and low torque; the efficiency is zero at zero speed and zero torque, since the mechanical power is τω.
  • No load current - The current required to spin the motor at the no load condition (i.e., the current needed to provide the torque necessary to overcome friction).
  • Nominal current (max. continuous current) - The current that yields the maximum continuous torque. This maximum is determined by thermal characteristics of the motor. The power dissipated by the motor as heat is i2R. Larger currents are acceptable intermittently, but large continuous currents may cause the motor to overheat.
  • Mechanical time constant - The time it takes the unloaded motor to reach 63% of its no load speed under a constant voltage, starting from rest. Proportional to the inertia of the rotor and inversely proportional to the square of the the torque constant.
  • Terminal inductance - The inductance of the motor windings.
  • Thermal resistance housing-ambient
  • Thermal resistance winding-housing
  • Thermal time constant winding.

Example

<extra type="library_actuators" id="libactuators">
  <technique profile="OpenRAVE">
    <actuator type="electric_motor" id="ExampleMotor1">
      <assigned_power_rating>1.0</assigned_power_rating>
      <max_speed>3000</max_speed>
      <no_load_speed>3990</no_load_speed>
      <nominal_torque>0.012</nominal_torque>
      <nominal_voltage>24.0</nominal_voltage>
      <rotor_inertia>0.0000023</rotor_inertia>
      <speed_constant>173.0</speed_constant>
      <speed_torque_gradient>130000.0</speed_torque_gradient>
      <starting_current>0.578</starting_current>
      <terminal_resistance>41.5</terminal_resistance>
      <torque_constant>0.0552</torque_constant>
    </actuator>
  </technique>
</extra>

attach_actuator

Introduction

Attaches an actuator to a joint.

Concepts

The actuator comes from the actuator library.

Related Elements

Parent elements <articulated_system>

Child Elements

Element Description Occurances
<instance_actuator> Instantiate an actuator. 1
<bind_actuator> Binds the actuator to a joint. 1

Attributes for <bind_actuator>

joint xs:token Required. The reference of the joint in the instantiated kinematics model that is part of the manipulator chain.

Example

<extra type="attach_actuator" name="motor0">
  <technique profile="OpenRAVE">
    <instance_actuator url="#ExampleMotor1"/>
    <bind_actuator joint="kmodel0/myjoint"/>
  </technique>
</extra>

<articulated_system>/<kinematics>/<technique_common>/<axis_info>

Extra parameters for each axis specified through the <newparam> element type.

COLLADA Usage

COLLADA Format Notes

  • articulated_system tag is used for saving both Robot and KinBody objects * if child is a motion tag, get accelerations and velocity limits from it
  • If <visual_scene> tag present, but no kinematics, then add each root node tree as a rigid link.
  • In order to set a static link in physics, use the <instance_rigid_body>/<dynamic> tag.

Hard and Soft Joint Limits

In many scenarios, the controllers on the robots use joints limits which are smaller than the maximum limits. The controller limits are called soft limits, while the hardware limits are called hard limits. In COLLADA, the specification is:

  • hard limits - specified inside the <joint> tag using the <limits> tag.
  • soft limits - specified inside the <articulated_system>/<kinematics>/<technique_common>/<axis_info> tag using the <limits> tag.

Storing Convex Decompositions

Each link is composed of a set of convex hulls. Need to create one geometry per convex hull (<convex_mesh>?) and specify multiple geometries per <node>.

Custom Data

OpenRAVE provides a user to hook up an XML writer and reader to a robot, which can be written as <extra> elements under any <articulated_system>.

OpenRAVE Database URI

OpenRAVE uses the $OPENRAVE_DATA environment variable to build its database of robots. Only files inside these directories can be accessed. Syntax:

openrave://[user[:password]@]host[:port]/path

Saving Scenes with Resource References

Although COLLADA is very flexible in terms of referencing libraries of models, in almost all cases, instantiating a robot will only change the following peices of information:

  • robot joint values
  • robot position
  • what bodies the robot is grabbing (dynamic_rigid_constraints)
  • joint limits

For most cases, the <kinematics_scene> defined in the separate robot file can be left intact and overrides can happen inside <instance_kinematics_scene>. For example, a minimal file that references a robot and sets joint0’s value to 1.5 is:

Unfortunately, COLLADA only allows one instance_kinematics_scene and one instance_visual_scene, which means that for multiple objects, the kinematics/physics/visual models have to be referenced directly instead of the scenes.

Instantiating Nodes with Similar Ids

When the same visual hierarchy nodes are instanced in the same scene like this:

<node name="body1">
  <translate>1 0 0</translate>
  <instance_node url="#somenode"/>
</node>
<node name="body2">
  <translate>1 0 0</translate>
  <instance_node url="#somenode"/>
</node>

The Ids fo the child nodes in #somenode will clash, therefore add a <extra> tag to allow suffixing of the Ids:

<node name="body1">
  <translate>1 0 0</translate>
  <instance_node url="#somenode">
    <extra type="idsuffix" name=".b1"/>
  </instance_node>
</node>
<node name="body2">
  <translate>1 0 0</translate>
  <instance_node url="#somenode">
    <extra type="idsuffix" name=".b2"/>
  </instance_node>
</node>

Composing Robots from Multiple Parts

Robots usually have grippers, robot arms, and robot bases in separate files, then we have one file that references all of them and specifies the links to merge together (ie, we do not complicate things by creating dummy joints). This can be done with articulated systems since <kinematics> tag supports multiple <instance_kinematics_model> tags.

Visibility/Collision Flags

Bodies can be initially invisible, but can still act as collision obstacles. Furthermore, there can exist nodes like plots and markers that should not act as kinbody elements or pertake in collision detection.

  • visibility is handled by geometry_info and is per-geometry.
  • colliding is handled by the collision/<link_collision_state>

TODO

Calibration vs Static Data

One thing that separates a base description of the robot from the real robot that will be used in labs is calibration:

  • where each sensor is with respect to the robot (6D pose)
  • intrinsic parameters for each sensor
  • joint offsets for encoder calibration
  • controller parameters like PID gains for dynamic properties of motors
  • possibly even link lengths depending on how much you trust the manufacturer

All these parameters will change per robot, and it won’t be a good idea asking every person to go and modify their one robot file. Instead there should have a different calibration file that the main collada file always references. It should be setup in such a way that the calibration file becomes optional.

Controllers

There is a <animation> element for containing trajectories and their targets. OpenRAVE will have to output animation data in this formation.

Contributors

Questions/Feedback

Having problems with OpenRAVE?