Format:COLLADA

From OpenRAVE
Revision as of 23:34, 15 March 2011 by Rdiankov (Talk | contribs) (Created page with "= COLLADA Robot Specification Version 0.1 = The [https://collada.org/mediawiki/index.php/COLLADA_-_Digital_Asset_and_FX_Exchange_Schema COLLADA] format is used to specify all ro...")

(diff) ← Older revision | Latest revision (diff) | Newer revision → (diff)
Jump to: navigation, search

Contents

COLLADA Robot Specification Version 0.1

The COLLADA format is used to specify all robot and scene related information. By default, COLLADA 1.5 handles geometry, visual effects, physical properties, and kinematics. This document describes how to extend the format to handle robot-specific information. An official example of a COLLADA extension can be found here.

COLLADA allows extensions of any of its tags using the <extra> tag. Each <extra> defines what type of information to provide (ie manipulator, sensor, collision), 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 <-> articulated_system
  • KinBody <-> kinematics_model
  • Sensor <-> sensor (new)

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.

Related Elements

Parent elements <articulated_system>, <kinematics_model>
Child elements See the following subsection.
Other

Child Elements

Element Description Occurrences
<interface> Contains the string id of the interface 1
<plugin> Optional. Contains the string of the location of the shared object object to load. 0 or 1

Example

<source lang="xml"> <extra type="interface_type">

 <technique profile="OpenRAVE">
   <interface>MyGenericRobot</interface>
   <plugin>myplugin.so</plugin>
 </technique>

</extra> </source>

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 Occurrences
<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 Occurrences
<translate> Translation. See main entry in Core. 0 or more
<rotate> Rotation axis. See main entry in Core. 0 or more

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 Occurrences
<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 Occurrences
<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'.

<source lang="xml"> <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>
   </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.so</plugin>
       </technique>
     </interface_type>
   </iksolver>
   <iksolver type="Translation3D">
     <free_joint joint="jointname4"/>
   </iksolver>
 </technique>

</extra> </source>

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>

Child Elements

Element Description Occurrences
<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

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.

Attributes for <ignore_link_pair>

link0 xs:token Required. References the SID of a <link> defined in <kinematics_model>. One of the links defining the pair to be ignored.
link1 xs:token Required. References the SID of a <link> defined in <kinematics_model>. One of the links defining the pair to be ignored.

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).

Example

<source lang="xml"> <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"/>
     </technique>
   </extra>

</library_kinematics_models> </source>

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 <kinematics_model>

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 Occurrences
<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.

Element Description Occurrences
<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 focal lengths, principal point, and skew. 1
<distortion> Contains a list_of_floats_type that specifies the distortion parameters: k1, k2, t1, t2, k3. 0 or 1

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.

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.

Element Description Occurrences
<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 Occurrences
<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.

Element Description Occurrences
<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:

type base_imu:

Element Description Occurrences
<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:

Element Description Occurrences
<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

<source lang="xml"> <extra type="library_sensors" id="libsensors">

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

</extra> </source>

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 Occurrences
<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 Occurrences
<translate> Translation. See main entry in Core. 0 or more
<rotate> Rotation axis. See main entry in Core. 0 or more

Example

<source lang="xml"> <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> </source>

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 Occurrences
<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

<source lang="xml"> <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> </source>

COLLADA Usage

Planning Weights

For each joint, a measure of how much a joint's movement impacts the robot (base joints have more impact than end effector joints). this information should be used by all planners to evaluate importance of joints. Calculating this accurately might require an offline process.

Composition

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 (<kinematics> tag supports multiple <instance_kinematics_model> tags).

Geometric Primitives

Use COLLADA <brep> for spheres, cylinders, boxes, etc.

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>.

Sensors

Physics

How to integrate physics data? If physics data is not present, treat all meshes as static?

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 we 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

Specifying controller parameters in the collada file falls somewhere in between calibration parameters and parameters that will never change and should be in the main robot file. In my opinion it is very hard to find static parameters especially when considering controllers in simulation along with real world controllers. Also, there's as many control algorithms out there as planners, and I wouldn't feel comfortable specifying planning algorithms and parameters inside a robot file.

COLLADA Format Notes

  • articulated_system tag is equivalent to OpenRAVE robot
    • if child is a motion tag, get accelerations and velocity limits from it
  • kinematics_model tag is equivalent to KinBody
  • If visual_scene tag present, but no kinematics, then add each node tree as a rigid link.

COLLADA Samples Using OpenRAVE Extensions

Robot Database

  • [old] the illustration of the "references" in the collada format is here . ( in dia format)

Contributors

  • University of Tokyo - Rosen Diankov and Ryohei Ueda