iai_kinematics_msgs

Summary

iai_kinematics_msgs
Version:

0.0.5

Description:

Ensemble of messages to communicate/request kinematics-related issues. NOTE/DISCLAIMER: A lot of these messages have been salvaged from now deprecated packages arm_navigation_msgs and kinematics_msgs. We acknowledge original authorship of these messages to all involved people (I, Georg, do not know them by name).

Maintainers:
  • Georg Bartels <georg DOT bartels AT cs DOT uni-bremen DOT de>
Licenses:
  • BSD
Authors:
  • Georg Bartels <georg DOT bartels AT cs DOT uni-bremen DOT de>
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

iai_kinematics_msgs/KDLWeights
Constant:
  • INVALID_MODE (byte):0
  • SET_TS (byte):1
  • SET_JS (byte):2
  • SET_LAMBDA (byte):4
  • SET_TS_JS (byte):3
Field:
  • mode (byte) –
  • weight_ts[36] (float64) –
  • weight_js[] (float64) –
  • lambda (float64) –
byte INVALID_MODE = 0
byte SET_TS = 1
byte SET_JS = 2
byte SET_LAMBDA = 4
byte SET_TS_JS = 3

byte mode                  # or-combination of values to set
float64[36] weight_ts      # the 6x6 matrix of task space weights in row-major order
float64[] weight_js        # the joints x joints matrix of joint space weights in row-major order
float64 lambda             # Lambda value
iai_kinematics_msgs/RobotState
Field:

This message contains information about the robot state, i.e. the positions of its joints and links

# This message contains information about the robot state, i.e. the positions of its joints and links
sensor_msgs/JointState joint_state
iai_kinematics_msgs/MultiDOFJointState multi_dof_joint_state
iai_kinematics_msgs/ErrorCodes
Field:
  • val (int32) –
Constant:
  • PLANNING_FAILED (int32):-1
  • SUCCESS (int32):1
  • TIMED_OUT (int32):-2
  • START_STATE_IN_COLLISION (int32):-3
  • START_STATE_VIOLATES_PATH_CONSTRAINTS (int32):-4
  • GOAL_IN_COLLISION (int32):-5
  • GOAL_VIOLATES_PATH_CONSTRAINTS (int32):-6
  • INVALID_ROBOT_STATE (int32):-7
  • INCOMPLETE_ROBOT_STATE (int32):-8
  • INVALID_PLANNER_ID (int32):-9
  • INVALID_NUM_PLANNING_ATTEMPTS (int32):-10
  • INVALID_ALLOWED_PLANNING_TIME (int32):-11
  • INVALID_GROUP_NAME (int32):-12
  • INVALID_GOAL_JOINT_CONSTRAINTS (int32):-13
  • INVALID_GOAL_POSITION_CONSTRAINTS (int32):-14
  • INVALID_GOAL_ORIENTATION_CONSTRAINTS (int32):-15
  • INVALID_PATH_JOINT_CONSTRAINTS (int32):-16
  • INVALID_PATH_POSITION_CONSTRAINTS (int32):-17
  • INVALID_PATH_ORIENTATION_CONSTRAINTS (int32):-18
  • INVALID_TRAJECTORY (int32):-19
  • INVALID_INDEX (int32):-20
  • JOINT_LIMITS_VIOLATED (int32):-21
  • PATH_CONSTRAINTS_VIOLATED (int32):-22
  • COLLISION_CONSTRAINTS_VIOLATED (int32):-23
  • GOAL_CONSTRAINTS_VIOLATED (int32):-24
  • JOINTS_NOT_MOVING (int32):-25
  • TRAJECTORY_CONTROLLER_FAILED (int32):-26
  • FRAME_TRANSFORM_FAILURE (int32):-27
  • COLLISION_CHECKING_UNAVAILABLE (int32):-28
  • ROBOT_STATE_STALE (int32):-29
  • SENSOR_INFO_STALE (int32):-30
  • NO_IK_SOLUTION (int32):-31
  • INVALID_LINK_NAME (int32):-32
  • IK_LINK_IN_COLLISION (int32):-33
  • NO_FK_SOLUTION (int32):-34
  • KINEMATICS_STATE_IN_COLLISION (int32):-35
  • INVALID_TIMEOUT (int32):-36
int32 val

# overall behavior
int32 PLANNING_FAILED=-1
int32 SUCCESS=1
int32 TIMED_OUT=-2

# start state errors
int32 START_STATE_IN_COLLISION=-3
int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4

# goal errors
int32 GOAL_IN_COLLISION=-5
int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6

# robot state
int32 INVALID_ROBOT_STATE=-7
int32 INCOMPLETE_ROBOT_STATE=-8

# planning request errors
int32 INVALID_PLANNER_ID=-9
int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
int32 INVALID_ALLOWED_PLANNING_TIME=-11
int32 INVALID_GROUP_NAME=-12
int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18

# state/trajectory monitor errors
int32 INVALID_TRAJECTORY=-19
int32 INVALID_INDEX=-20
int32 JOINT_LIMITS_VIOLATED=-21
int32 PATH_CONSTRAINTS_VIOLATED=-22
int32 COLLISION_CONSTRAINTS_VIOLATED=-23
int32 GOAL_CONSTRAINTS_VIOLATED=-24
int32 JOINTS_NOT_MOVING=-25
int32 TRAJECTORY_CONTROLLER_FAILED=-26

# system errors
int32 FRAME_TRANSFORM_FAILURE=-27
int32 COLLISION_CHECKING_UNAVAILABLE=-28
int32 ROBOT_STATE_STALE=-29
int32 SENSOR_INFO_STALE=-30

# kinematics errors
int32 NO_IK_SOLUTION=-31
int32 INVALID_LINK_NAME=-32
int32 IK_LINK_IN_COLLISION=-33
int32 NO_FK_SOLUTION=-34
int32 KINEMATICS_STATE_IN_COLLISION=-35

# general errors
int32 INVALID_TIMEOUT=-36
iai_kinematics_msgs/KinematicSolverInfo
Field:

A list of joints in the kinematic tree

# A list of joints in the kinematic tree
string[] joint_names
# A list of joint limits corresponding to the joint names
iai_kinematics_msgs/JointLimits[] limits
# A list of links that the kinematics node provides solutions for
string[] link_names
iai_kinematics_msgs/JointLimits
Field:
  • joint_name (string) –
  • has_position_limits (bool) –
  • min_position (float64) –
  • max_position (float64) –
  • has_velocity_limits (bool) –
  • max_velocity (float64) –
  • has_acceleration_limits (bool) –
  • max_acceleration (float64) –

This message contains information about limits of a particular joint (or control dimension)

# This message contains information about limits of a particular joint (or control dimension)
string joint_name

# true if the joint has position limits
bool has_position_limits

# min and max position limits
float64 min_position
float64 max_position

# true if joint has velocity limits
bool has_velocity_limits

# max velocity limit
float64 max_velocity
# min_velocity is assumed to be -max_velocity

# true if joint has acceleration limits
bool has_acceleration_limits
# max acceleration limit
float64 max_acceleration
# min_acceleration is assumed to be -max_acceleration
iai_kinematics_msgs/PositionIKRequest
Field:

A Position IK request message The name of the link for which we are computing IK

# A Position IK request message
# The name of the link for which we are computing IK
string ik_link_name

# The (stamped) pose of the link
geometry_msgs/PoseStamped pose_stamped

# A RobotState consisting of hint/seed positions for the IK computation. 
# These may be used to seed the IK search. 
# The seed state MUST contain state for all joints to be used by the IK solver
# to compute IK. The list of joints that the IK solver deals with can be found using
# the kinematics_msgs/GetKinematicSolverInfo
iai_kinematics_msgs/RobotState ik_seed_state

# Additional state information can be provided here to specify the starting positions 
# of other joints/links on the robot.
iai_kinematics_msgs/RobotState robot_state
iai_kinematics_msgs/MultiDOFJointState
Field:
  • stamp (time) –
  • joint_names[] (string) –
  • frame_ids[] (string) –
  • child_frame_ids[] (string) –
  • poses[] (geometry_msgs/Pose) –

A representation of a multi-dof joint state

#A representation of a multi-dof joint state
time stamp
string[] joint_names
string[] frame_ids
string[] child_frame_ids
geometry_msgs/Pose[] poses

Service types

iai_kinematics_msgs/GetKinematicSolverInfo
Field (Response):
 

A service call to get more information about the solver used by a node performing kinematics

# A service call to get more information about the solver used by a node performing kinematics
---
iai_kinematics_msgs/KinematicSolverInfo kinematic_solver_info
iai_kinematics_msgs/GetPositionIK
Field (Request):
 
Field (Response):
 

A service call to carry out an inverse kinematics computation The inverse kinematics request

# A service call to carry out an inverse kinematics computation
# The inverse kinematics request
iai_kinematics_msgs/PositionIKRequest ik_request
# Maximum allowed time for IK calculation
duration timeout
---
# The returned solution 
# (in the same order as the list of joints specified in the IKRequest message)
iai_kinematics_msgs/RobotState solution

iai_kinematics_msgs/ErrorCodes error_code
iai_kinematics_msgs/GetPositionFK
Field (Request):
 
Field (Response):
 

A service definition for a standard forward kinematics service The frame_id in the header message is the frame in which the forward kinematics poses will be returned

# A service definition for a standard forward kinematics service
# The frame_id in the header message is the frame in which 
# the forward kinematics poses will be returned
Header header

# A vector of link name for which forward kinematics must be computed
string[] fk_link_names

# A robot state consisting of joint names and joint positions to be used for forward kinematics
iai_kinematics_msgs/RobotState robot_state
---
# The resultant vector of PoseStamped messages that contains the (stamped) poses of the requested links
geometry_msgs/PoseStamped[] pose_stamped

# The list of link names corresponding to the poses
string[] fk_link_names

iai_kinematics_msgs/ErrorCodes error_code
iai_kinematics_msgs/GetWeightedIK
Field (Request):
 
Field (Response):
 

the desired pose of the tool frame

# the desired pose of the tool frame
geometry_msgs/PoseStamped pose

# tool frame defauts to x_wrist_roll_link
geometry_msgs/Pose tool_frame

# the joint space configuration to resolve redundancy
sensor_msgs/JointState ik_seed

# Weight matrices for IK solver
iai_kinematics_msgs/KDLWeights weights

---
sensor_msgs/JointState solution

iai_kinematics_msgs/ErrorCodes error_code