def __init__(self):

        # This checks if the head camera is open.  If it isn't, this will
        # close the left hand camera.
        try:
            CameraController('head_camera')
        except AttributeError:
            left_cam = CameraController('left_hand_camera')
            left_cam.close()

        head_cam = CameraController('head_camera')
        head_cam.resolution = (1280, 800)
        head_cam.open()

        # Creating the head variable to mess with later
        self.head = Head()
        self.head.set_pan(angle=0.)

        # Field of view
        self.CENTER_X = int(1280 / 2)
        self.FOV = pi / 3

        # Range away from center you want the arm to stop within
        self.FACE_RANGE = 50

        self.FACE_CASCADE = cv2.CascadeClassifier(
            'src/baxter_face_tracking_demos/src' +
            '/haarcascade_frontalface_default.xml')
        self.EYE_CASCADE = cv2.CascadeClassifier(
            'src/baxter_face_tracking_demos/src/haarcascade_eye.xml')

        self.subscription = rospy.Subscriber('/cameras/head_camera/image',
                                             Image, self.send)
        rospy.on_shutdown(self.leave_subs_n_pubs)
Exemple #2
0
    def __init__(self, calibrate_grippers=True):
        self._baxter_state = RobotEnable()

        self._left = Limb(LEFT)
        self._right = Limb(RIGHT)

        self._limbs = {LEFT: self._left, RIGHT: self._right}

        self._head = Head()
        self._left_gripper, self._right_gripper = Gripper(LEFT), Gripper(RIGHT)
        if calibrate_grippers:
            self.calibrate()

        self._left_ikservice = IKService(LEFT)
        self._right_ikservice = IKService(RIGHT)
Exemple #3
0
    def __init__(self, camera_averaging=False):
        self._cvbr = CvBridge()

        self.rs = RobotEnable()
        self.ik = IKHelper()

        camera_topic = '/cameras/{0}_camera/image_rect'
        if camera_averaging:
            camera_topic += '_avg'

        self.left_img = None
        self._left_camera_sub = rospy.Subscriber(
            camera_topic.format('left_hand'), Image,
            self._on_left_imagemsg_received)

        self.right_img = None
        self._right_camera_sub = rospy.Subscriber(
            camera_topic.format('right_hand'), Image,
            self._on_right_imagemsg_received)

        self.head_img = None
        self._head_camera_sub = rospy.Subscriber(
            camera_topic.format('head'), Image,
            self._on_head_imagemsg_received)

        self.left_itb = None
        self._left_itb_sub = rospy.Subscriber('/robot/itb/left_itb/state',
                                              ITBState,
                                              self._on_left_itbmsg_received)

        self.right_itb = None
        self._right_itb_sub = rospy.Subscriber('/robot/itb/right_itb/state',
                                               ITBState,
                                               self._on_right_itbmsg_received)

        self.left_gripper = Gripper('left')
        self.right_gripper = Gripper('right')

        self.head = Head()

        self._display_pub = rospy.Publisher('/robot/xdisplay',
                                            Image,
                                            tcp_nodelay=True,
                                            latch=True)
Exemple #4
0
import rospy
import baxter_interface
from baxter_interface import Gripper, Limb, Head
import time

rospy.init_node('test')

left = Limb('left')
right = Limb('right')
leftg = Gripper('left')
head = Head()


def dab():
    right.move_to_neutral()
    left.move_to_neutral()

    dableft = {
        'left_w0': -0.10316020798529407,
        'left_w1': 0.0790000105760988,
        'left_w2': -0.0011504855909140602,
        'left_e0': -0.006519418348513008,
        'left_e1': -0.039883500485020755,
        'left_s0': 0.29682528245582757,
        'left_s1': -0.6181942575178218
    }

    dabright = {
        'right_s0': 0.6810874698211237,
        'right_s1': -0.4935583185021319,
        'right_w0': -0.008820389530341128,
Exemple #5
0
 def __init__(self):
     self.head = Head()
     self.halo = Halo()
     self.halo.set_off()