habitat.articulated_agents.MobileManipulatorParams class

Data to configure a mobile manipulator.

Special methods

def __init__(self, arm_joints: typing.List[int], gripper_joints: typing.List[int], wheel_joints: typing.Optional[typing.List[int]], arm_init_params: typing.Optional[numpy.ndarray], gripper_init_params: typing.Optional[numpy.ndarray], ee_offset: typing.List[_magnum.Vector3], ee_links: typing.List[int], ee_constraint: numpy.ndarray, cameras: typing.Dict[str, ArticulatedAgentCameraParams], gripper_closed_state: numpy.ndarray, gripper_open_state: numpy.ndarray, gripper_state_eps: float, arm_mtr_pos_gain: float, arm_mtr_vel_gain: float, arm_mtr_max_impulse: float, wheel_mtr_pos_gain: typing.Optional[float], wheel_mtr_vel_gain: typing.Optional[float], wheel_mtr_max_impulse: typing.Optional[float], base_offset: _magnum.Vector3, base_link_names: typing.Set[str], ee_count: typing.Optional[int] = 1) -> None
Method generated by attrs for class MobileManipulatorParams.

Properties

arm_init_params: typing.Optional[numpy.ndarray] get set del
The starting joint angles of the arm. If None, resets to 0.
arm_joints: typing.List[int] get set del
The joint ids of the arm joints.
arm_mtr_max_impulse: float get set del
The maximum impulse of the arm motor.
arm_mtr_pos_gain: float get set del
The position gain of the arm motor.
arm_mtr_vel_gain: float get set del
The velocity gain of the arm motor.
base_offset: _magnum.Vector3 get set del
The offset of the root transform from the center ground point for navmesh kinematic control.
cameras: typing.Dict[str, ArticulatedAgentCameraParams] get set del
The cameras and where they should go. The key is the prefix to match in the sensor names. For example, a key of “head”`will match sensors `”head_rgb” and “head_depth”
ee_constraint: numpy.ndarray get set del
A (ee_count, 2, N) shaped array specifying the upper and lower limits for each end-effector joint where N is the arm DOF.
ee_count: typing.Optional[int] get set del
how many end effectors
A list with the Habitat Sim link ID of the end-effector.
ee_offset: typing.List[_magnum.Vector3] get set del
The 3D offset from the end-effector link to the true end-effector position.
gripper_closed_state: numpy.ndarray get set del
All gripper joints must achieve this state for the gripper to be considered closed.
gripper_init_params: typing.Optional[numpy.ndarray] get set del
The starting joint positions of the gripper. If None, resets to 0.
gripper_joints: typing.List[int] get set del
The habitat sim joint ids of any grippers.
gripper_open_state: numpy.ndarray get set del
All gripper joints must achieve this state for the gripper to be considered open.
gripper_state_eps: float get set del
Error margin for detecting whether gripper is closed.
wheel_joints: typing.Optional[typing.List[int]] get set del
The joint ids of the wheels. If the wheels are not controlled, then this should be None
wheel_mtr_max_impulse: typing.Optional[float] get set del
The maximum impulse of the wheel motor (if there are wheels).
wheel_mtr_pos_gain: typing.Optional[float] get set del
The position gain of the wheeled motor (if there are wheels).
wheel_mtr_vel_gain: typing.Optional[float] get set del
The velocity gain of the wheel motor (if there are wheels).