def getAnglesPosition(self, joint_names): """ Overloads @getAnglesPosition from the @RobotVirtual class. Handles the finger mimicked position for the hands (when getting the position of RHand or LHand, will return the hand's opening percentage). Parameters: joint_names - List of string (or string if only one joint) containing the name of the joints Returns: joint_positions - List of float (or float if only one joint) containing the joint's positions in radians """ if type(joint_names) is str: names = [joint_names] else: names = list(joint_names) joint_positions = RobotVirtual.getAnglesPosition(self, names) for hand, finger in zip( ["RHand", "LHand"], ["RFinger11", "LFinger11"]): for i in range(names.count(hand)): index = names.index(hand) joint_positions[index] =\ RobotVirtual.getAnglesPosition(self, [finger]).pop() /\ (1/(self.joint_dict[finger].getUpperLimit() - self.joint_dict[finger].getLowerLimit())) +\ self.joint_dict[finger].getLowerLimit() if len(joint_positions) == 1: return joint_positions.pop() else: return joint_positions
def getAnglesVelocity(self, joint_names): """ Overloads @getAnglesVelocity from the @RobotVirtual class. The method won't return the velocity of RHand and LHand joints. Parameters: joint_names - List of string (or string if only one joint) containing the name of the joints Returns: joint_velocities - List of float (or float if only one joint) containing the joint's velocities in rad/s """ if type(joint_names) is str: names = [joint_names] else: names = list(joint_names) joint_velocities = RobotVirtual.getAnglesVelocity(self, names) if len(joint_velocities) == 1: return joint_velocities.pop() else: return joint_velocities
def loadRobot(self, translation, quaternion, physicsClientId=0): """ Overloads @loadRobot from the @RobotVirtual class, loads the robot into the simulated instance. This method also updates the max velocity of the robot's fingers, adds self collision filters to the model and defines the cameras of the model in the camera_dict. Parameters: translation - List containing 3 elements, the translation [x, y, z] of the robot in the WORLD frame quaternion - List containing 4 elements, the quaternion [x, y, z, q] of the robot in the WORLD frame physicsClientId - The id of the simulated instance in which the robot is supposed to be loaded """ pybullet.setAdditionalSearchPath(os.path.dirname( os.path.realpath(__file__)), physicsClientId=physicsClientId) # Add 0.50 meters on the z component, avoing to spawn NAO in the ground translation = [translation[0], translation[1], translation[2] + 1.05] RobotVirtual.loadRobot(self, translation, quaternion, physicsClientId=physicsClientId) balance_constraint = pybullet.createConstraint( parentBodyUniqueId=self.robot_model, parentLinkIndex=-1, childBodyUniqueId=-1, childLinkIndex=-1, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0], parentFramePosition=[0, 0, 0], parentFrameOrientation=[0, 0, 0, 1], childFramePosition=translation, childFrameOrientation=quaternion, physicsClientId=self.physics_client) self.goToPosture("Stand", 1.0) pybullet.setCollisionFilterPair(self.robot_model, self.robot_model, self.link_dict["REye"].getIndex(), self.link_dict["LEye"].getIndex(), 0, physicsClientId=self.physics_client) for link in ["torso", "HeadRoll_link"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["NeckPitch_link"].getIndex(), self.link_dict[link].getIndex(), 0, physicsClientId=self.physics_client) for side in ["R", "L"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Eye"].getIndex(), self.link_dict["HeadRoll_link"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Thigh"].getIndex(), self.link_dict["body"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side.lower() + "_ankle"].getIndex(), self.link_dict[side + "Tibia"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "ShoulderYaw_link"].getIndex(), self.link_dict["torso"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "WristRoll_link"].getIndex(), self.link_dict[side.lower() + "_wrist"].getIndex(), 0, physicsClientId=self.physics_client) for link in ["ShoulderYaw_link", "WristYaw_link"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + link].getIndex(), self.link_dict[side + "Elbow"].getIndex(), 0, physicsClientId=self.physics_client) for name, link in self.link_dict.items(): if side + "Finger" in name or\ side + "Thumb" in name: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side.lower() + "_wrist"].getIndex(), link.getIndex(), 0, physicsClientId=self.physics_client) for joint in self.joint_dict.values(): pybullet.resetJointState(self.robot_model, joint.getIndex(), 0.0, physicsClientId=self.physics_client) pybullet.removeConstraint(balance_constraint, physicsClientId=self.physics_client) for joint_name in list(self.joint_dict): if 'RFinger' in joint_name or 'RThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["RHand"].getMaxVelocity()) elif 'LFinger' in joint_name or 'LThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["LHand"].getMaxVelocity()) camera_right = CameraRgb( self.robot_model, RomeoVirtual.ID_CAMERA_RIGHT, self.link_dict["CameraRightEye_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client) camera_left = CameraRgb(self.robot_model, RomeoVirtual.ID_CAMERA_LEFT, self.link_dict["CameraLeftEye_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client) camera_depth = CameraDepth(self.robot_model, RomeoVirtual.ID_CAMERA_DEPTH, self.link_dict["CameraDepth_optical_frame"], hfov=58.0, vfov=45.0, physicsClientId=self.physics_client) self.camera_dict = { RomeoVirtual.ID_CAMERA_RIGHT: camera_right, RomeoVirtual.ID_CAMERA_LEFT: camera_left, RomeoVirtual.ID_CAMERA_DEPTH: camera_depth } # The frequency of the IMU is set to 100Hz self.imu = Imu(self.robot_model, self.link_dict["torso"], 100.0, physicsClientId=self.physics_client)
def loadRobot(self, translation, quaternion, physicsClientId=0): """ Overloads @loadRobot from the @RobotVirtual class. Update max velocity for the fingers and thumbs, based on the hand joints. Add self collision exceptions (The biceps won't autocollide with the torso, the fingers and thumbs of a hand won't autocollide with the corresponding wrist). Add the cameras. Add motion constraint. """ pybullet.setAdditionalSearchPath(os.path.dirname( os.path.realpath(__file__)), physicsClientId=physicsClientId) RobotVirtual.loadRobot(self, translation, quaternion, physicsClientId=physicsClientId) for base_link in ["Hip", "Pelvis"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[base_link].getIndex(), 0, physicsClientId=self.physics_client) for shoulder_roll_link in ["RBicep", "LBicep"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[shoulder_roll_link].getIndex(), 0, physicsClientId=self.physics_client) for name, link in self.link_dict.items(): for wrist in ["r_wrist", "l_wrist"]: if wrist[0] + "finger" in name.lower() or\ wrist[0] + "thumb" in name.lower(): pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[wrist].getIndex(), link.getIndex(), 0, physicsClientId=self.physics_client) for joint_name in list(self.joint_dict): if 'RFinger' in joint_name or 'RThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["RHand"].getMaxVelocity()) elif 'LFinger' in joint_name or 'LThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["LHand"].getMaxVelocity()) elif "Wheel" in joint_name: self.joint_dict.pop(joint_name) self.camera_top = CameraRgb(self.robot_model, self.link_dict["CameraTop_optical_frame"], hfov=56.3, vfov=43.7, physicsClientId=self.physics_client) self.camera_bottom = CameraRgb( self.robot_model, self.link_dict["CameraBottom_optical_frame"], hfov=56.3, vfov=43.7, physicsClientId=self.physics_client) self.camera_depth = CameraDepth( self.robot_model, self.link_dict["CameraDepth_optical_frame"], hfov=58.0, vfov=45.0, physicsClientId=self.physics_client) self.motion_constraint = pybullet.createConstraint( parentBodyUniqueId=self.robot_model, parentLinkIndex=-1, childBodyUniqueId=-1, childLinkIndex=-1, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0], parentFramePosition=[0, 0, 0], parentFrameOrientation=[0, 0, 0, 1], childFramePosition=[translation[0], translation[1], 0], childFrameOrientation=quaternion, physicsClientId=self.physics_client) self.laser_manager = Laser(self.robot_model, self.link_dict["Tibia"].getIndex(), physicsClientId=self.physics_client) self.base_controller = PepperBaseController( self.robot_model, [self.linear_velocity, self.angular_velocity], [self.linear_acceleration, self.angular_acceleration], self.motion_constraint, physicsClientId=self.physics_client) self.goToPosture("StandZero", 1.0)
def loadRobot(self, translation, quaternion, physicsClientId=0): """ Overloads @loadRobot from the @RobotVirtual class, loads the robot into the simulated instance. This method also updates the max velocity of the robot's fingers, adds self collision filters to the model and defines the cameras of the model in the camera_dict. Parameters: translation - List containing 3 elements, the translation [x, y, z] of the robot in the WORLD frame quaternion - List containing 4 elements, the quaternion [x, y, z, q] of the robot in the WORLD frame physicsClientId - The id of the simulated instance in which the robot is supposed to be loaded """ pybullet.setAdditionalSearchPath( os.path.dirname(os.path.realpath(__file__)), physicsClientId=physicsClientId) # Add 0.36 meters on the z component, avoing to spawn NAO in the ground translation = [translation[0], translation[1], translation[2] + 0.36] RobotVirtual.loadRobot( self, translation, quaternion, physicsClientId=physicsClientId) balance_constraint = pybullet.createConstraint( parentBodyUniqueId=self.robot_model, parentLinkIndex=-1, childBodyUniqueId=-1, childLinkIndex=-1, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0], parentFramePosition=[0, 0, 0], parentFrameOrientation=[0, 0, 0, 1], childFramePosition=translation, childFrameOrientation=quaternion, physicsClientId=self.physics_client) self.goToPosture("Stand", 1.0) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict["Head"].getIndex(), 0, physicsClientId=self.physics_client) for side in ["R", "L"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Thigh"].getIndex(), self.link_dict[side + "Hip"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Bicep"].getIndex(), self.link_dict[side + "ForeArm"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Pelvis"].getIndex(), self.link_dict[side + "Thigh"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Tibia"].getIndex(), self.link_dict[side.lower() + "_ankle"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Finger11_link"].getIndex(), self.link_dict[side + "Finger13_link"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Finger21_link"].getIndex(), self.link_dict[side + "Finger23_link"].getIndex(), 0, physicsClientId=self.physics_client) for base_link in ["RThigh", "LThigh", "RBicep", "LBicep"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[base_link].getIndex(), 0, physicsClientId=self.physics_client) for name, link in self.link_dict.items(): for wrist in ["r_wrist", "l_wrist"]: if wrist[0] + "finger" in name.lower() or\ wrist[0] + "thumb" in name.lower(): pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[wrist].getIndex(), link.getIndex(), 0, physicsClientId=self.physics_client) for joint in self.joint_dict.values(): pybullet.resetJointState( self.robot_model, joint.getIndex(), 0.0, physicsClientId=self.physics_client) pybullet.removeConstraint( balance_constraint, physicsClientId=self.physics_client) for joint_name in list(self.joint_dict): if 'RFinger' in joint_name or 'RThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["RHand"].getMaxVelocity()) elif 'LFinger' in joint_name or 'LThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["LHand"].getMaxVelocity()) camera_top = CameraRgb( self.robot_model, NaoVirtual.ID_CAMERA_TOP, self.link_dict["CameraTop_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client) camera_bottom = CameraRgb( self.robot_model, NaoVirtual.ID_CAMERA_BOTTOM, self.link_dict["CameraBottom_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client) self.camera_dict = { NaoVirtual.ID_CAMERA_TOP: camera_top, NaoVirtual.ID_CAMERA_BOTTOM: camera_bottom} # The frequency of the IMU is set to 100Hz self.imu = Imu( self.robot_model, self.link_dict["torso"], 100.0, physicsClientId=self.physics_client) # FSRs fsr_dict = dict() for name in NaoFsr.LFOOT + NaoFsr.RFOOT: fsr_dict[name] = Fsr( self.robot_model, self.link_dict[name], physicsClientId=self.physics_client) self._setFsrHandler(FsrHandler(fsr_dict))
def loadRobot(self, translation, quaternion, physicsClientId=0): """ Overloads @loadRobot from the @RobotVirtual class. Update max velocity for the fingers and thumbs, based on the hand joints. Add self collision exceptions. Add the cameras. """ pybullet.setAdditionalSearchPath(os.path.dirname( os.path.realpath(__file__)), physicsClientId=physicsClientId) # Add 0.36 meters on the z component, avoing to spawn NAO in the ground translation = [translation[0], translation[1], translation[2] + 0.36] RobotVirtual.loadRobot(self, translation, quaternion, physicsClientId=physicsClientId) balance_constraint = pybullet.createConstraint( parentBodyUniqueId=self.robot_model, parentLinkIndex=-1, childBodyUniqueId=-1, childLinkIndex=-1, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0], parentFramePosition=[0, 0, 0], parentFrameOrientation=[0, 0, 0, 1], childFramePosition=translation, childFrameOrientation=quaternion, physicsClientId=self.physics_client) self.goToPosture("Stand", 1.0) pybullet.setCollisionFilterPair(self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict["Head"].getIndex(), 0, physicsClientId=self.physics_client) for side in ["R", "L"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Thigh"].getIndex(), self.link_dict[side + "Hip"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Bicep"].getIndex(), self.link_dict[side + "ForeArm"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Pelvis"].getIndex(), self.link_dict[side + "Thigh"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Tibia"].getIndex(), self.link_dict[side.lower() + "_ankle"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Finger11_link"].getIndex(), self.link_dict[side + "Finger13_link"].getIndex(), 0, physicsClientId=self.physics_client) pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[side + "Finger21_link"].getIndex(), self.link_dict[side + "Finger23_link"].getIndex(), 0, physicsClientId=self.physics_client) for base_link in ["RThigh", "LThigh", "RBicep", "LBicep"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[base_link].getIndex(), 0, physicsClientId=self.physics_client) for name, link in self.link_dict.items(): for wrist in ["r_wrist", "l_wrist"]: if wrist[0] + "finger" in name.lower() or\ wrist[0] + "thumb" in name.lower(): pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[wrist].getIndex(), link.getIndex(), 0, physicsClientId=self.physics_client) pybullet.removeConstraint(balance_constraint, physicsClientId=self.physics_client) for joint_name in list(self.joint_dict): if 'RFinger' in joint_name or 'RThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["RHand"].getMaxVelocity()) elif 'LFinger' in joint_name or 'LThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["LHand"].getMaxVelocity()) self.camera_top = CameraRgb(self.robot_model, self.link_dict["CameraTop_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client) self.camera_bottom = CameraRgb( self.robot_model, self.link_dict["CameraBottom_optical_frame"], hfov=60.9, vfov=47.6, physicsClientId=self.physics_client)
def __init__(self): """ Constructor """ RobotVirtual.__init__(self, "wrong_description_filepath")
def loadRobot(self, translation, quaternion, physicsClientId=0): """ Overloads @loadRobot from the @RobotVirtual class, loads the robot into the simulated instance. This method also updates the max velocity of the robot's fingers, adds self collision filters to the model, adds a motion constraint to the model and defines the cameras of the model in the camera_dict. Parameters: translation - List containing 3 elements, the translation [x, y, z] of the robot in the WORLD frame quaternion - List containing 4 elements, the quaternion [x, y, z, q] of the robot in the WORLD frame physicsClientId - The id of the simulated instance in which the robot is supposed to be loaded Returns: boolean - True if the method ran correctly, False otherwise """ pybullet.setAdditionalSearchPath( os.path.dirname(os.path.realpath(__file__)), physicsClientId=physicsClientId) RobotVirtual.loadRobot( self, translation, quaternion, physicsClientId=physicsClientId) for base_link in ["Hip", "Pelvis"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[base_link].getIndex(), 0, physicsClientId=self.physics_client) for shoulder_roll_link in ["RBicep", "LBicep"]: pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict["torso"].getIndex(), self.link_dict[shoulder_roll_link].getIndex(), 0, physicsClientId=self.physics_client) for name, link in self.link_dict.items(): for wrist in ["r_wrist", "l_wrist"]: if wrist[0] + "finger" in name.lower() or\ wrist[0] + "thumb" in name.lower(): pybullet.setCollisionFilterPair( self.robot_model, self.robot_model, self.link_dict[wrist].getIndex(), link.getIndex(), 0, physicsClientId=self.physics_client) for joint_name in list(self.joint_dict): if 'RFinger' in joint_name or 'RThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["RHand"].getMaxVelocity()) elif 'LFinger' in joint_name or 'LThumb' in joint_name: self.joint_dict[joint_name].setMaxVelocity( self.joint_dict["LHand"].getMaxVelocity()) elif "Wheel" in joint_name: self.joint_dict.pop(joint_name) camera_top = CameraRgb( self.robot_model, PepperVirtual.ID_CAMERA_TOP, self.link_dict["CameraTop_optical_frame"], hfov=56.3, vfov=43.7, physicsClientId=self.physics_client) camera_bottom = CameraRgb( self.robot_model, PepperVirtual.ID_CAMERA_BOTTOM, self.link_dict["CameraBottom_optical_frame"], hfov=56.3, vfov=43.7, physicsClientId=self.physics_client) camera_depth = CameraDepth( self.robot_model, PepperVirtual.ID_CAMERA_DEPTH, self.link_dict["CameraDepth_optical_frame"], hfov=58.0, vfov=45.0, physicsClientId=self.physics_client) self.camera_dict = { PepperVirtual.ID_CAMERA_TOP: camera_top, PepperVirtual.ID_CAMERA_BOTTOM: camera_bottom, PepperVirtual.ID_CAMERA_DEPTH: camera_depth} self.motion_constraint = pybullet.createConstraint( parentBodyUniqueId=self.robot_model, parentLinkIndex=-1, childBodyUniqueId=-1, childLinkIndex=-1, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0], parentFramePosition=[0, 0, 0], parentFrameOrientation=[0, 0, 0, 1], childFramePosition=[translation[0], translation[1], 0], childFrameOrientation=quaternion, physicsClientId=self.physics_client) self.laser_manager = Laser( self.robot_model, self.link_dict["Tibia"].getIndex(), physicsClientId=self.physics_client) self.base_controller = PepperBaseController( self.robot_model, [self.linear_velocity, self.angular_velocity], [self.linear_acceleration, self.angular_acceleration], self.motion_constraint, physicsClientId=self.physics_client) self.goToPosture("StandZero", 1.0)
def __init__(self, pathImageTexture=None, rgba=None): RobotVirtual.__init__(self, URDF_SPHERE) self.path_image_texture = pathImageTexture self.rgba = rgba self.scale = 1 self.texture_id = None
def loadRobot(self, physicsClientId=0): """ Dummy overload to test the loadRobot method """ RobotVirtual.loadRobot(self, [0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 1.0], physicsClientId=physicsClientId)
def __init__(self): """ Constructor """ RobotVirtual.__init__(self, DummyVirtual.URDF_PATH)