ArticulatedModel¶
- class mplib.ArticulatedModel¶
Bases:
pybind11_objectSupports initialization from URDF and SRDF files, and provides access to underlying Pinocchio and FCL models.
- __init__(
- self: mplib.pymp.ArticulatedModel,
- urdf_filename: str,
- srdf_filename: str,
- *,
- name: str = None,
- gravity: numpy.ndarray[numpy.float64[3, 1]] = array([0., 0., -9.81]),
- link_names: list[str] = [],
- joint_names: list[str] = [],
- convex: bool = False,
- verbose: bool = False,
Construct an articulated model from URDF and SRDF files.
- Parameters:
urdf_filename – path to URDF file, can be relative to the current working directory
srdf_filename – path to SRDF file, we use it to disable self-collisions
name – name of the articulated model to override URDF robot name attribute
gravity – gravity vector, by default is
[0, 0, -9.81]in -z axislink_names – list of links that are considered for planning
joint_names – list of joints that are considered for planning
convex – use convex decomposition for collision objects. Default:
False.verbose – print debug information. Default:
False.
- property base_pose¶
The base (root) pose of the robot
- static create_from_urdf_string(
- urdf_string: str,
- srdf_string: str,
- collision_links: list[mplib.pymp.collision_detection.fcl.FCLObject],
- *,
- name: str = None,
- gravity: numpy.ndarray[numpy.float64[3, 1]] = array([0., 0., -9.81]),
- link_names: list[str] = [],
- joint_names: list[str] = [],
- verbose: bool = False,
Constructs an ArticulatedModel from URDF/SRDF strings and collision links
- Parameters:
urdf_string – URDF string (without visual/collision elements for links)
srdf_string – SRDF string (only disable_collisions element)
collision_links – Vector of collision links as FCLObjectPtr. Format is:
[FCLObjectPtr, ...]. The collision objects are at the shape’s local_pose.name – name of the articulated model to override URDF robot name attribute
gravity – gravity vector, by default is
[0, 0, -9.81]in -z axislink_names – list of links that are considered for planning
joint_names – list of joints that are considered for planning
verbose – print debug information. Default:
False.
- Returns:
a unique_ptr to ArticulatedModel
- get_base_pose(self: mplib.pymp.ArticulatedModel) mplib.pymp.Pose¶
Get the base (root) pose of the robot.
- Returns:
base pose of the robot
- get_fcl_model(
- self: mplib.pymp.ArticulatedModel,
Get the underlying FCL model.
- Returns:
FCL model used for collision checking
- get_move_group_end_effectors(
- self: mplib.pymp.ArticulatedModel,
Get the end effectors of the move group.
- Returns:
list of end effectors of the move group
- get_move_group_joint_indices(
- self: mplib.pymp.ArticulatedModel,
Get the joint indices of the move group.
- Returns:
list of user joint indices of the move group
- get_move_group_joint_names(
- self: mplib.pymp.ArticulatedModel,
Get the joint names of the move group.
- Returns:
list of joint names of the move group
- get_move_group_qpos_dim(self: mplib.pymp.ArticulatedModel) int¶
Get the dimension of the move group qpos.
- Returns:
dimension of the move group qpos
- get_name(self: mplib.pymp.ArticulatedModel) str¶
Get name of the articulated model.
- Returns:
name of the articulated model
- get_pinocchio_model(
- self: mplib.pymp.ArticulatedModel,
Get the underlying Pinocchio model.
- Returns:
Pinocchio model used for kinematics and dynamics computations
- get_pose(self: mplib.pymp.ArticulatedModel) mplib.pymp.Pose¶
Get the base (root) pose of the robot.
- Returns:
base pose of the robot
- get_qpos(
- self: mplib.pymp.ArticulatedModel,
Get the current joint position of all active joints inside the URDF.
- Returns:
current qpos of all active joints
- get_user_joint_names(self: mplib.pymp.ArticulatedModel) list[str]¶
Get the joint names that the user has provided for planning.
- Returns:
list of joint names of the user
- get_user_link_names(self: mplib.pymp.ArticulatedModel) list[str]¶
Get the link names that the user has provided for planning.
- Returns:
list of link names of the user
- property name¶
Name of the articulated model
- property pose¶
The base (root) pose of the robot
- property qpos¶
Current qpos of all active joints
- set_base_pose(
- self: mplib.pymp.ArticulatedModel,
- pose: mplib.pymp.Pose,
Set the base pose of the robot and update all collision links in the
FCLModel.- Parameters:
pose – base pose of the robot
- set_move_group(*args, **kwargs)¶
Overloaded function.
set_move_group(self: mplib.pymp.ArticulatedModel, end_effector: str) -> None
Set the move group, i.e. the chain ending in end effector for which to compute the forward kinematics for all subsequent queries.
- Parameters:
end_effector – name of the end effector link
set_move_group(self: mplib.pymp.ArticulatedModel, end_effectors: list[str]) -> None
Set the move group but we have multiple end effectors in a chain. I.e., Base –> EE1 –> EE2 –> … –> EEn
- Parameters:
end_effectors – list of links extending to the end effector
- set_pose(
- self: mplib.pymp.ArticulatedModel,
- pose: mplib.pymp.Pose,
Set the base pose of the robot and update all collision links in the
FCLModel.- Parameters:
pose – base pose of the robot
- set_qpos(
- self: mplib.pymp.ArticulatedModel,
- qpos: numpy.ndarray[numpy.float64[m, 1]],
- full: bool = False,
Set the current joint positions and update all collision links in the
FCLModel.- Parameters:
qpos – current qpos of all active joints or just the move group joints
full – whether to set the full qpos or just the move group qpos. If full is
False, we will pad the missing joints with current known qpos. The default isFalse
- update_SRDF(self: mplib.pymp.ArticulatedModel, SRDF: str) None¶
Update the SRDF file to disable self-collisions.
- Parameters:
srdf – path to SRDF file, can be relative to the current working directory