iai_kinematics_msgs¶
Contents:
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¶
Service types¶
iai_kinematics_msgs/GetKinematicSolverInfo
iai_kinematics_msgs/GetPositionIK
iai_kinematics_msgs/GetPositionFK
iai_kinematics_msgs/GetWeightedIK
-
iai_kinematics_msgs/GetKinematicSolverInfo
¶ Field (Response): - kinematic_solver_info (iai_kinematics_msgs/KinematicSolverInfo) –
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): - ik_request (iai_kinematics_msgs/PositionIKRequest) –
- timeout (duration) –
Field (Response): - solution (iai_kinematics_msgs/RobotState) –
- error_code (iai_kinematics_msgs/ErrorCodes) –
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): - header (std_msgs/Header) –
- fk_link_names[] (string) –
- robot_state (iai_kinematics_msgs/RobotState) –
Field (Response): - pose_stamped[] (geometry_msgs/PoseStamped) –
- fk_link_names[] (string) –
- error_code (iai_kinematics_msgs/ErrorCodes) –
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): - pose (geometry_msgs/PoseStamped) –
- tool_frame (geometry_msgs/Pose) –
- ik_seed (sensor_msgs/JointState) –
- weights (iai_kinematics_msgs/KDLWeights) –
Field (Response): - solution (sensor_msgs/JointState) –
- error_code (iai_kinematics_msgs/ErrorCodes) –
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