Robot.forward_kinematics
-
Robot.
forward_kinematics
(configuration, group=None, backend=None, link_name=None)[source] Calculate the robot’s forward kinematic.
- Parameters
full_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 (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 world’s coordinate system (WCF).
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) >>> frame_WCF_m = robot.forward_kinematics(configuration, group, backend='model') >>> frame_WCF_c == frame_WCF_m True