zonopyrobots.dynamics.pzrnea#
- zonopyrobots.dynamics.pzrnea(rotatotopes: Dict[str, MPZType | BMPZType] | List[MPZType | BMPZType] | None, qd: Dict[str, PZType | BPZType] | List[PZType | BPZType] | None, qd_aux: Dict[str, PZType | BPZType] | List[PZType | BPZType] | None, qdd: Dict[str, PZType | BPZType] | List[PZType | BPZType] | None, robot: ZonoArmRobot, zono_order: int = 40, gravity: torch.Tensor | np.ndarray = torch.tensor, link_mass_override: Dict[str, Any] = None, link_center_mass_override: Dict[str, Any] = None, link_inertia_override: Dict[str, Any] = None) OrderedDictType[str, Dict[str, PZType | BPZType | torch.Tensor]] [source]#
RNEA for an arm robot using Polynomial Zonotopes
This is implemented based the description of the Iterative Newton-Euler Algorithm (RNEA) described in John J. Craig’s “Introduction to Robotics: Mechanics and Control” 3rd Edition, Chapter 6.5. ISBN: 978-0-201-54361-2.
- Parameters:
rotatotopes (Union[Dict[str, Union[matPolyZonotope, batchMatPolyZonotope]], List[Union[matPolyZonotope, batchMatPolyZonotope]], None]) – Dictionary of rotatotopes for each joint, or a list of rotatotopes for each joint. If a list is provided, it is assumed to be in the same order as the actuated joints in the URDF. If not provided, it will use the identity matrix for each joint.
qd (Union[Dict[str, Union[polyZonotope, batchPolyZonotope]], List[Union[polyZonotope, batchPolyZonotope]], None]) – Dictionary of joint velocities for each joint, or a list of joint velocities for each joint. If a list is provided, it is assumed to be in the same order as the actuated joints in the URDF. If not provided, it will use 0 for each joint.
qd_aux (Union[Dict[str, Union[polyZonotope, batchPolyZonotope]], List[Union[polyZonotope, batchPolyZonotope]], None]) – Dictionary of joint auxillary velocities for each joint, or a list of joint auxillary velocities for each joint. If a list is provided, it is assumed to be in the same order as the actuated joints in the URDF. If not provided, it will use the same value as qd.
qdd (Union[Dict[str, Union[polyZonotope, batchPolyZonotope]], List[Union[polyZonotope, batchPolyZonotope]], None]) – Dictionary of joint accelerations for each joint, or a list of joint accelerations for each joint. If a list is provided, it is assumed to be in the same order as the actuated joints in the URDF. If not provided, it will use 0 for each joint.
robot (ZonoArmRobot) – The robot to use for the RNEA
zono_order (int, optional) – The order of the zonotopes to use. Lower is faster but less accurate. Defaults to 40.
gravity (Union[torch.Tensor, np.ndarray], optional) – The gravity vector to use. Defaults to [0, 0, -9.81].
link_mass_override (Dict[str, Any], optional) – Dictionary of link masses to override the URDF values. Defaults to None.
link_center_mass_override (Dict[str, Any], optional) – [description]. Dictionary of link center of masses to override the URDF values. Defaults to None.
link_inertia_override (Dict[str, Any], optional) – [description]. Dictionary of link inertias to override the URDF values. Defaults to None.
- Returns:
Dictionary of joint dynamics. Each entry is a dictionary with keys ‘force’, ‘moment’, and ‘torque’ (if applicable).
- Return type:
OrderedDictType[str, Dict[str, Union[polyZonotope, batchPolyZonotope, torch.Tensor]]]