Robot.forward_kinematics

Robot.forward_kinematics(configuration, group=None, backend=None, link_name=None)[source]

Calculate the robot’s forward kinematic.

Parameters
  • configuration (compas_fab.robots.Configuration) – The configuration to calculate the forward kinematic for.

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

  • backend (None or str) – If None calculates fk with the client if it exists or with the robot model. If ‘model’ use the robot model to calculate fk. Anything else is open for implementation, possibly ‘kdl’, ‘ikfast’

  • link_name (str, optional) – The name of the link to calculate the forward kinematics for. Defaults to the group’s end effector link.

Returns

Frame – The frame in the robot’s coordinate system (RCF).

Examples

>>> configuration = Configuration.from_revolute_values([-2.238, -1.153, -2.174, 0.185, 0.667, 0.000])
>>> group = robot.main_group_name
>>> frame_RCF_c = robot.forward_kinematics(configuration, group)
>>> frame_RCF_m = robot.forward_kinematics(configuration, group, backend='model')
>>> frame_RCF_c == frame_RCF_m
True
>>> frame_WCF = robot.to_world_coords(frame_RCF_m, group)
>>> frame_WCF
Frame(Point(0.300, 0.100, 0.500), Vector(1.000, -0.000, -0.000), Vector(0.000, 1.000, -0.000))