Kinematic Solvers

Created by Rico Stodt, Modified on Mon, 14 Feb, 2022 at 1:48 PM by Rico Stodt

Inverse Kinematics Solver Service


The robot software provides a simple Position Inverse Kinematics (IK) Solver as a ROS Service. Specify a desired Cartesian coordinate and orientation for an Endpoint (in world x,y,z space), and the solver will return a set of joint angles that will get the arm there - or return an Invalid state if the pose is unreachable. An optional seed to start looking for solutions around can be specified as a joint angle configuration.

Note that the service takes an array of requests, and similarly returns an array of results with corresponding indexes. Similarly, optional seeds for each Endpoint request can be provided in a corresponding array of the same size as the requests array. This multiple array structure is a common structure used in ROS and explained in the sensor_msgs/JointState message.

SolvePositionIK Service [srv]
/ExternalTools/<side>/PositionKinematicsNode/IKService (intera_core_msgs/SolvePositionIK.srv)

  • Request
    • pose_stamp (Required) - an array of geometry_msgs/PoseStamped requests, each defining the Cartesian <x,y,z> Position and Quaternion orientation of the Endpoint in the /base TF frame.
    • (Optional) seed_angles - an array of joint configuration seeds to start searching for solutions around, corresponding to each request in pose_stamp, where each individual seed is defined as a JointState message with the joint names and positions filled for all the arm Joints (so seed_angles is an array of arrays).
    • (Optional) seed_mode - specify the IK solver strategy for what types of seeds to use. By default (SEED_AUTO), the solver will iterate through the different strategies, starting with the user provided seed if it exists, until a solution is found. However, by explicitly setting the seed_mode to a specific mode, the solver will only return whether it was able to find a solution using that type of seed. The different mode types are defined as constants in the message (default: SEED_AUTO):
      •     int8 SEED_AUTO    = 0
            int8 SEED_USER    = 1
            int8 SEED_CURRENT = 2
            int8 SEED_NS_MAP  = 3
        
            int8 seed_mode

    • use_nullspace_goal (Required) - for each IK request, tells whether it should use the nullspace goal in bool type.
    • nullspace_goal - if use null space goal, providing the full set or subset of joint angles, it will be the null space goal. The message type will be sensor_msgs/JointState[].
    • (Optional) nullspace_gain - the gain used to bias toward the nullspace goal. Must be [0.0, 1.0], type in float64, if empty, the default gain of 0.4 will be used.
    • tip_names (Required) - tip name for each pose IK.
  • Response
    • result_type - will be a corresponding array of uint8's, which will be -1 if no valid IK solution was found for the given Endpoint request; it will be -2 if IK solution is in self collision. otherwise, it will be negative and correspond to the type of seed eventually used that gave a valid solution. These values correspond to the constants in the message used to specify seed_mode.
    • joints will contain joint solutions corresponding to each Endpoint request. Note that you should always check the result_type field to see if a valid joint solution was found, as invalid joint solutions can be returned in this array.

This service allows users to solve for basic IK joint angle solutions or perform workspace validation. The service will use a number of seeding strategies to find a solution. These strategies can be specified explicitly or just use the default to find the first solution in the possible methods. Optionally a Joint configuration can optionally be provided as a seed to the Solver.

Check Inverse Kinematics Solver Example for more details.


Forward Kinematics Solver Service


The robot software also provides Forward Position Kinematics (IK) Solver as a ROS Service, joint positions(s) to request Forward-Kinematics joint solutions for sensor_msgs/JointState[] configuration.

  • Request
    • tip_names (Required) - tip name for each pose FK in string type.
  • Response
    • pose_stamp - solution(s) per FK call, geometry_msgs/PoseStamped[]
    • isValid - will be a corresponding boolean which will be True if a valid endpoint solution was found for the given joint positions request.

Check Forward Kinematics Solver Example for more details.

Was this article helpful?

That’s Great!

Thank you for your feedback

Sorry! We couldn't be helpful

Thank you for your feedback

Let us know how can we improve this article!

Select at least one of the reasons
CAPTCHA verification is required.

Feedback sent

We appreciate your effort and will try to fix the article