Robot.forward_kinematics

Robot.forward_kinematics(configuration, group=None, use_attached_tool_frame=True, options=None)[source]

Calculate the robot’s forward kinematic.

Parameters
  • configuration (compas_fab.robots.Configuration) – The full configuration to calculate the forward kinematic for. If no full configuration is passed, the zero-joint state for the other configurable joints is assumed.

  • group (obj:str, optional) – The planning group used for the calculation. Defaults to the robot’s main planning group.

  • use_attached_tool_frame (bool, optional) – If True and there is a tool attached to the planning group, FK will return the TCF of the attached tool instead of the T0CF. Defaults to True.

  • options (obj:dict, optional) – Dictionary containing the following key-value pairs:

    • "solver": (str, optional) If None calculates FK with the client if it exists or with the robot model. If 'model' use the robot model to calculate FK. Other values depend on specific backend implementation, some backends might allow selecting different FK solvers dynamically.

    • "link": (str, optional) The name of the link to calculate the forward kinematics for. Defaults to the group’s end effector link. Backwards compatibility note: if there’s no link option, the planner will try also ee_link as fallback before defaulting to the end effector’s link.

    There are additional options that are specific to the backend in use. Check the API reference of the FK backend implementation for more details.

Returns

compas.geometry.Frame – The frame in the world’s coordinate system (WCF).

Raises
  • ValueError – If link_name doesn’t match any of the Robot instance’s links.

  • NotImplementedError – If forward kinematic method for given backend is not implemented.

Examples

>>> configuration = Configuration.from_revolute_values([-2.238, -1.153, -2.174, 0.185, 0.667, 0.000])
>>> group = robot.main_group_name
>>> frame_WCF_c = robot.forward_kinematics(configuration, group)
>>> options = {'solver': 'model'}
>>> frame_WCF_m = robot.forward_kinematics(configuration, group, options)
>>> frame_WCF_c == frame_WCF_m
True