habitat_sim.robots.MobileManipulator class

Robot with a controllable base and arm.

Methods

def _update_motor_settings_cache(self)
Updates the JointMotorSettings cache for cheaper future updates
def _validate_arm_ctrl_input(self, ctrl: typing.List[float])
Raises an exception if the control input is NaN or does not match the joint dimensions.
def calculate_ee_forward_kinematics(self, joint_state: numpy.ndarray) -> numpy.ndarray
Gets the end-effector position for the given joint state.
def calculate_ee_inverse_kinematics(self, ee_target_position: numpy.ndarray) -> numpy.ndarray
Gets the joint states necessary to achieve the desired end-effector configuration.
def clip_ee_to_workspace(self, pos: numpy.ndarray) -> numpy.ndarray
Clips a 3D end-effector position within region the robot can reach.
def close_gripper(self) -> None
Set gripper to the close state
Get a string listing all robot link and joint names for debugging purposes.
def get_robot_sim_id(self) -> int
Get the unique id for referencing the robot.
def open_gripper(self) -> None
Set gripper to the open state
def reconfigure(self) -> None
Instantiates the robot the scene. Loads the URDF, sets initial state of parameters, joints, motors, etc…
def reset(self) -> None
Reset the joints on the existing robot. NOTE: only arm and gripper joint motors (not gains) are reset by default, derived class should handle any other changes.
def set_fixed_arm_joint_pos(self, fix_arm_joint_pos)
Will fix the arm to a desired position at every internal timestep. Can be used for kinematic arm control.
def set_gripper_target_state(self, gripper_state: float) -> None
Set the gripper motors to a desired symmetric state of the gripper [0,1] -> [open, closed]
def update(self) -> None
Updates the camera transformations and performs necessary checks on joint limits and sleep states.

Special methods

def __init__(self, params: MobileManipulatorParams, urdf_path: str, sim: simulator.Simulator, limit_robo_joints: bool = True, fixed_base: bool = True)
Constructor

Properties

arm_joint_limits: typing.Tuple[numpy.ndarray, numpy.ndarray] get
Get the arm joint limits in radians
arm_joint_pos: numpy.ndarray get set
Get the current arm joint positions.
arm_motor_pos: numpy.ndarray get set
Get the current target of the arm joints motors.
arm_velocity: numpy.ndarray get
Get the velocity of the arm joints.
base_pos get set
Get the robot base ground position via configured local offset from origin.
base_rot: float get set
base_transformation get
Gets the Habitat Sim link id of the end-effector.
ee_local_offset: magnum.Vector3 get
Gets the relative offset of the end-effector center from the end-effector link.
ee_transform: magnum.Matrix4 get
Gets the transformation of the end-effector location. This is offset from the end-effector link location.
gripper_joint_pos: numpy.ndarray get set
Get the current gripper joint positions.
is_gripper_closed: bool get
True if all gripper joints are within eps of the closed state.
is_gripper_open: bool get
True if all gripper joints are within eps of the open state.

Method documentation

def habitat_sim.robots.MobileManipulator.__init__(self, params: MobileManipulatorParams, urdf_path: str, sim: simulator.Simulator, limit_robo_joints: bool = True, fixed_base: bool = True)

Constructor

Parameters
params
urdf_path
sim
limit_robo_joints If true, joint limits of robot are always enforced.
fixed_base