URDF.pl

 has_urdf(+Object, +RootObject) is semidet
True if Object is a part of RootObject, and RootObject is assigned to some URDF description.
Arguments:
Part- IRI atom
Root- IRI atom
 urdf_load(+Object, +File) is semidet
Same as urdf_load/3 with empty options list.
Arguments:
Object- IRI atom
File- Path to URDF file
 urdf_load(+Object, +File, +Options) is semidet
Assert a URDF file as description of an object. This is primarly done to associate parts of the object to links described in the URDF file. Links and joints in the URDF file may further be mapped to a RDF model and asserted to the triple store.
Arguments:
Object- IRI atom
File- Path to URDF file
Options- List of options
 urdf_set_pose_to_origin(+Object, +Frame) is semidet
Same as urdf_set_pose/2 but assigns the base of the URDF to be located exactly at the frame given in the second argument.
Arguments:
Object- IRI atom
Frame- URDF frame name atom
 urdf_set_pose(+Object, +Pose) is semidet
Assign the initial pose of links described in URDF as the current pose of link entities. This requires that the load_rdf option was used in urdf_load/3. The base link of the URDF is assigned to the transform given in the second argument.
Arguments:
Object- IRI atom
Frame- A pose list of frame-position-quaternion
 is_urdf_link(?Entity) is semidet
 is_urdf_joint(?Entity) is semidet
 has_base_link_name(?Obj, ?Name) is semidet
 has_end_link_name(?Obj, ?Name) is semidet
 has_base_link(?Obj, ?Link) is semidet
 has_end_link(?Obj, ?Link) is semidet
 has_child_link(?Joint, ?Link) is semidet
 has_parent_link(?Joint, ?Link) is semidet
 urdf_robot_name(+Object, -Name) is semidet
Get the name of the currently loaded robot.
 urdf_root_link(+Object, -Name) is semidet
Get the name of the root link of the robot.
 urdf_link_parent_joint(+Object, +LinkName, -JointName) is semidet
Get the name of the parent joint of a link.
 urdf_link_child_joints(+Object, +LinkName, -JointNames) is semidet
Get the list of joint names of all child joints of a link.
 urdf_link_inertial(+Object, +LinkName, -Inertia, -Origin, -Mass) is semidet
Get the inertial origin of a link as a pose w.r.t. the origin frame of a link.

Inertia matrices are coded as a list: [XX, XY, XZ, YY, YZ, ZZ]. For an explanation, visit: http://wiki.ros.org/urdf/XML/link

 urdf_joint_type(+Object, +JointName, Type) is semidet
Get the type of a joint. Possible types: revolute, prismatic, continuous, fixed, floating, planar, and unknown.
 urdf_joint_child_link(+Object, +JointName, -LinkName) is semidet
Get the name of the link of a joint.
 urdf_joint_parent_link(+Object, +JointName, -LinkName) is semidet
Get the name the parent link of a joint.
 urdf_joint_axis(+Object, +JointName, -Axis) is semidet
Get the axis of a joint, expressed as a list [X, Y, Z].
 urdf_joint_origin(+Object, +JointName, -Origin) is semidet
Get the origin of a joint, expressed as a pose w.r.t. the link frame of its parent link.

Poses are coded as a compound term: pose([X,Y,Z],[QX,QY,QZ,QW]), with the orientation represented as Quaternion.

 urdf_joint_damping(+Object, +JointName, -Damping) is semidet
Read the damping value of a joint.
 urdf_joint_friction(+Object, +JointName, -Friction) is semidet
Get the static friction value of a joint.
 urdf_joint_hard_limits(+Object, +JointName, -PosLimits, -VelMax, -EffMax) is semidet
Read the hard limits of a joint.
 urdf_joint_soft_limits(+Object, +JointName, -PosLimits, -KP, -KV) is semidet
Read the soft limits of a joint.

Undocumented predicates

The following predicates are exported, but not or incorrectly documented.

 urdf_joint_names(Arg1, Arg2)
 urdf_joint_calibration_falling(Arg1, Arg2, Arg3)
 urdf_link_names(Arg1, Arg2)
 urdf_link_collision_shape(Arg1, Arg2, Arg3, Arg4)
 urdf_init
 urdf_joint_calibration_rising(Arg1, Arg2, Arg3)
 urdf_link_visual_shape(Arg1, Arg2, Arg3, Arg4, Arg5, Arg6)