예제 #1
0
    def __init__(self, hostname, username, password, flip, speed_control, frame_id="axis_camera",
                 use_encrypted_password=False, state_publishing_frequency=50, camera_id=1):
        """Initialize the PTZ driver and start publishing positional data.

        :param hostname: Hostname of the camera (without http://, can be an IP address).
        :type hostname: basestring
        :param username: If login is needed, provide a username here.
        :type username: basestring|None
        :param password: If login is needed, provide a password here.
        :type password: basestring|None
        :param flip: Whether to flip the controls (for ceiling-mounted cameras). Deprecated.
        :type flip: bool
        :param speed_control: Use speed control instead of positional. Deprecated.
        :type speed_control: bool
        :param frame_id: Id of the frame in which positinal data should be published.
        :type frame_id: basestring
        :param use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True).
        :type use_encrypted_password: bool
        :param state_publishing_frequency: The frequency at which joint states should be published.
        :type state_publishing_frequency: int
        :param camera_id: ID (number) of the camera. Can be 1 to 4.
        :type camera_id: int
        """

        self._hostname = hostname
        self._camera_id = camera_id
        self._frame_id = frame_id

        self._state_publishing_frequency = state_publishing_frequency

        self._executing_reconfigure = False
        self._reconfigure_mutex = threading.Lock()

        self._api = None
        # autodetect the VAPIX API and connect to it; try it forever
        while self._api is None and not rospy.is_shutdown():
            try:
                self._api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password)
            except (IOError, ValueError):
                rospy.loginfo(
                    "Retrying connection to VAPIX on host %s, camera %d in 2 seconds." % (hostname, camera_id))
                rospy.sleep(2)
        if rospy.is_shutdown():
            return

        if not self._api.has_ptz():
            raise RuntimeError("Camera %d on host %s doesn't have a Pan-Tilt-Zoom unit." % (self._camera_id, self._hostname))

        # Create a controller of the camera
        self._camera_controller = AxisCameraController(self._api, self, flip_vertically=flip, flip_horizontally=flip)

        # BACKWARDS COMPATIBILITY LAYER
        self.username = username  # deprecated
        self.password = password  # deprecated
        self.flip = flip  # deprecated
        self.speedControl = speed_control  # deprecated
        self.mirror = False  # deprecated

        self.msg = None  # deprecated
        self.cmdString = ""  # deprecated

        self.pub = rospy.Publisher("state", Axis, queue_size=100)  # deprecated
        self.command_subscriber = rospy.Subscriber("cmd", Axis, self.cmd, queue_size=100)  # deprecated
        self.mirror_subscriber = rospy.Subscriber("mirror", Bool, self.mirrorCallback, queue_size=100)  # deprecated

        self.srv = Server(PTZConfig, self.callback)  # deprecated

        # Needs to be after the backwards compatibility setup
        # start the publisher thread
        self._publisher_thread = PositionStreamingThread(self, self._api)
        self.st = self._publisher_thread  # deprecated
        self._publisher_thread.start()
예제 #2
0
    def _publish_frames_until_error(self):
        """Continuous loop to publish images. Stops if an error occurs while reading the stream.

        Should also account for pausing/resuming (stop/start reading the stream), and video parameters changes.
        These should not make this function exit, it should instead reconnect automatically.
        """
        while not rospy.is_shutdown():  # publish until an error occurs (then, a return is called to end this loop)

            # if we are paused, wait for a resume before connecting to the stream
            while not rospy.is_shutdown() and (self._is_paused or not self._is_video_ok()):
                rospy.sleep(1)

            try:  # now try to open the video stream;
                with closing(
                        self._axis._api.get_video_stream(self._axis._fps, self._axis._resolution.name, self._axis._compression,
                                                         self._axis._use_color, self._axis._use_square_pixels)
                ) as stream:

                    self.fp = stream  # backwards compatibility

                    # this is the rate at which we wake up to read new data; there is no need for it to happen faster
                    # than at the requested FPS
                    rate = rospy.Rate(self._axis._fps)

                    # we've just crerated a video stream with the most recently requested parameters, so clear the dirty
                    # flag
                    self._axis.video_params_changed = False

                    # publish images from the stream until i) someone pauses us, or ii) video parameters changed
                    # when one of these events happens, we take a next iteration of the outermost loop, in which there
                    # is a wait in case of pausing, and a new video stream connection is created with most recent
                    # parameters
                    while not rospy.is_shutdown() and not self._axis.video_params_changed and not self._is_paused:
                        try:
                            (header, image) = VAPIX.read_next_image_from_video_stream(stream)
                            if image is not None:
                                timestamp = rospy.Time.now()
                                self._publish_image(header, image, timestamp)
                                self._publish_camera_info(header, image, timestamp)
                            else:
                                # probably a temporary error, don't return
                                rospy.logwarn("Retrieving image from Axis camera failed.")
                        except IOError, e:
                            # error occured, we should therefore return
                            rospy.loginfo('Error reading from the video stream. Cause: %r' % e)
                            return

                        # read images only on the requested FPS frequency
                        rate.sleep()

            except IOError, e:
                # could not open the stream, the camera is probably in standby mode?
                if self._axis.auto_wakeup_camera:
                    wakeup_succeeded = self._wakeup_camera()
                    if not wakeup_succeeded:
                        # if we could not wake up the camera, it is an error and we should return
                        rospy.logerr("%r" % e)
                        return
                    else:
                        continue
                else:
                    # if we cannot open the stream and auto-wakeup is off, we have no other possibility than to report
                    # error
                    rospy.logerr("%r" % e)
                    return

            # the image-publishing loop has been interrupted, so reconnect to the stream in the next
            # outer-while iteration

            if self._axis.video_params_changed:
                rospy.logdebug("Video parameters changed, reconnecting the video stream with the new ones.")
예제 #3
0
 def getImageData(self):
     """Deprecated."""
     if self.content_length > 0:
         self.img = VAPIX._get_image_data_from_stream(self.fp, self.content_length)
예제 #4
0
 def getHeader(self):
     """Deprecated."""
     self.header = VAPIX._get_image_header_from_stream(self.fp)
     self.content_length = int(self.header['Content-Length'])
예제 #5
0
 def findBoundary(self):
     """Deprecated."""
     VAPIX._find_boundary_in_stream(self.fp)
예제 #6
0
    def __init__(self, hostname, username, password, width, height, frame_id, camera_info_url, use_encrypted_password,
                 camera_id=1, auto_wakeup_camera=True, compression=0, fps=24, use_color=True,
                 use_square_pixels=False):
        """Create the ROS-VAPIX interface.

        :param hostname: Hostname of the camera (without http://, can be an IP address).
        :type hostname: basestring
        :param username: If login is needed, provide a username here.
        :type username: :py:obj:`basestring` | None
        :param password: If login is needed, provide a password here.
        :type password: :py:obj:`basestring` | None
        :param width: Width of the requested video stream in pixels (can be changed later). Must be one of the supported
                      resolutions. If `None`, the resolution will be chosen by height only. If also `height` is `None`,
                      then the default camera resolution will be used.
        :type width: int|None
        :param height: Height of the requested video stream in pixels (can be changed later). Must be one of the
                       supported resolutions. If `None`, the resolution will be chosen by width only. If also `width` is
                       `None`, then the default camera resolution will be used.
        :type height: int|None
        :param frame_id: The ROS TF frame assigned to the camera.
        :type frame_id: basestring
        :param camera_info_url: The URL pointing to the camera calaibration, if available.
        :type camera_info_url: basestring
        :param use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True).
        :type use_encrypted_password: bool
        :param camera_id: ID (number) of the camera. Can be 1 to 4.
        :type camera_id: int
        :param auto_wakeup_camera: If True, there will be a wakeup trial after first unsuccessful network command.
        :type auto_wakeup_camera: bool
        :param compression: Compression of the image (0 - no compression, 100 - max compression).
        :type compression: int
        :param fps: The desired frames per second.
        :type fps: int
        :param use_color: If True, send a color stream, otherwise send only grayscale image.
        :type use_color: bool
        :param use_square_pixels: If True, the resolution will be stretched to match 1:1 pixels.
                                  By default, the pixels have a ratio of 11:12.
        :type use_square_pixels: bool
        :raises: :py:exc:`ValueError` if the requested resolution (either the `resolution`, or `width`+`height`
                 is not supported.
        """
        # True every time the video parameters have changed and the URL has to be altered (set from other threads).
        self.video_params_changed = False

        self.__initializing = True

        self._hostname = hostname
        self._camera_id = camera_id

        self.diagnostic_updater = Updater()
        self.diagnostic_updater.setHardwareID(hostname)

        self._api = None
        # autodetect the VAPIX API and connect to it; try it forever
        while self._api is None and not rospy.is_shutdown():
            try:
                self._api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password)
            except (IOError, ValueError):
                rospy.loginfo("Retrying connection to VAPIX on host %s, camera %d in 2 seconds." %
                              (hostname, camera_id))
                rospy.sleep(2)
        if rospy.is_shutdown():
            return

        self._allowed_resolutions = self._get_allowed_resolutions()

        rospy.loginfo("The following resolutions are available for camera %d:\n%s" %
                      (camera_id, "\n".join([str(res) for res in self._allowed_resolutions])))
        rospy.set_param("~allowed_resolutions", [res.get_vapix_representation() for res in self._allowed_resolutions])

        # Sometimes the camera falls into power saving mode and stops streaming.
        # This setting allows the script to try to wake up the camera.
        self._auto_wakeup_camera = auto_wakeup_camera

        # dynamic-reconfigurable properties - definitions
        self._width = None  # deprecated
        self._height = None  # deprecated
        self._resolution = None
        self._compression = None
        self._fps = None
        self._use_color = None
        self._use_square_pixels = None

        # treat empty strings as None in width and height params
        width = width if width != "" else None
        height = height if height != "" else None

        # dynamic-reconfigurable properties - defaults
        if width is None and height is None:
            # TODO change to perform default resolution detection from VAPIX
            self.set_resolution(self._allowed_resolutions[0])
        else:
            resolution = self.find_resolution_by_size(width, height)
            self.set_resolution(resolution.get_vapix_representation())

        self.set_compression(compression)
        self.set_fps(fps)
        self.set_use_color(use_color)
        self.set_use_square_pixels(use_square_pixels)

        # only advertise the supported resolutions on dynamic reconfigure
        change_enum_items(
            VideoStreamConfig,
            "resolution",
            [{
                'name': res.name if isinstance(res, CIFVideoResolution) else str(res),
                'value': res.get_vapix_representation(),
                'description': str(res)
            } for res in self._allowed_resolutions],
            self._resolution.get_vapix_representation()
        )

        # dynamic reconfigure server
        self._video_stream_param_change_server = dynamic_reconfigure.server.Server(VideoStreamConfig,
                                                                                   self.reconfigure_video)

        # camera info setup
        self._frame_id = frame_id
        self._camera_info_url = camera_info_url

        # generate a valid camera name based on the hostname
        self._camera_name = camera_info_manager.genCameraName(self._hostname)
        self._camera_info = camera_info_manager.CameraInfoManager(cname=self._camera_name, url=self._camera_info_url)
        self._camera_info.loadCameraInfo()  # required before getCameraInfo()

        # the thread used for streaming images (is instantiated when the first image subscriber subscribes)
        self._streaming_thread = None

        # the publishers are started/stopped lazily in peer_subscribe/peer_unsubscribe
        self._video_publisher_frequency_diagnostic = FrequencyStatusParam({'min': self._fps, 'max': self._fps})
        self._video_publisher = PausableDiagnosedPublisher(
            self,
            rospy.Publisher("image_raw/compressed", CompressedImage, self, queue_size=100),
            self.diagnostic_updater, self._video_publisher_frequency_diagnostic, TimeStampStatusParam()
        )
        self._camera_info_publisher = PausableDiagnosedPublisher(
            self,
            rospy.Publisher("camera_info", CameraInfo, self, queue_size=100),
            self.diagnostic_updater, self._video_publisher_frequency_diagnostic, TimeStampStatusParam()
        )

        self._snapshot_server = rospy.Service("take_snapshot", TakeSnapshot, self.take_snapshot)

        self.diagnostic_updater.add(FunctionDiagnosticTask("Camera parameters", self._camera_diagnostic_callback))

        # BACKWARDS COMPATIBILITY LAYER

        self.username = username  # deprecated
        self.password = password  # deprecated
        self.use_encrypted_password = use_encrypted_password  # deprecated
        self.st = None  # deprecated
        self.pub = self._video_publisher  # deprecated
        self.caminfo_pub = self._camera_info_publisher  # deprecated

        self.__initializing = False