.. _tutorial_campod: Camera Pod Operation ====================== **Note: This tutorial is applicable for the Kerloud 600 UAV equipped with a camera pod only** .. image:: ../img/campod/campod_view.png :height: 600 px :width: 750 px :scale: 60 % :align: center The camera pod is a commonly used equipment in UAVs for aerial mapping, video/image monitoring, visual tracking and localization. We offer users an advanced option for streamlined video monitoring and processing, `the Kerloud 600 Pro-Cam Pod `_, which can be used as a baseline for outdoor surveillance application. With a software-ready environment, users can build their own applications with ease, such as video transmission and real-time visual recognition with deep learning neural networks. Here we illustrate how to access the onboard vision, and manipulate the camera pod in ROS environment. Video and Image Acquisition ---------------------------- The default camera pod model in the Kerloud 600 Pro-Cam Pod supports 1080P 60fps video stream, and 10x optical zoom. The specification enables the UAV to recognize cars in 1000 meters, as depicted below: .. image:: ../img/campod/cam_zoom.png :height: 300 px :width: 750 px :scale: 100 % :align: center We prepare the software environment ready for users to retrieve the onboard video stream and image. To view the live video from the camera pod, run commands below: :: cd ~/src/catkinws_periph bash view_campod_video.sh The video will show as: .. image:: ../img/campod/cam_video_viewsnap.png :height: 350 px :width: 750 px :scale: 100 % :align: center To publish the online image in the ROS environment, run commands: :: cd ~/src/catkinws_periph bash pub_campod_image.sh The image topic can be viewed via rqt_image_view command .. image:: ../img/campod/cam_imag_ros_view.png :height: 350 px :width: 750 px :scale: 100 % :align: center Camera Pod Manipulation --------------------------- Service Details ^^^^^^^^^^^^^^^^^^^^ The default camera pod model supports user manipulations including camera attitude commanding, zooming, focusing, video capturing and photo taking. These manipulations are realized by service from our ROS driver provided in the directory **~/src/catkinws_periph/src/campod_driver**. Details for the service is listed below, but users are strongly recommended to refer to the README file of the driver package to stay updated with the latest version. :: # command to turn on/off the motors uint8 SET_MOTOR_ON_OFF = 0 # params[0]: 0 for turn off, 1 for turn on # command to set camera attitude uint8 SET_CAMPOD_ATTITUE = 1 # params[0-2]: set 1 to enable roll, pitch, yaw channels in order; # params[3-5]: desired attitude angle in degrees # command to set camera attitude rates uint8 SET_CAMPOD_ATTITUDE_RATE = 2 # params[0-2]: set 1 to enable roll, pitch, yaw channels in order; # params[3-5]: desired attitude rate in degrees # command to request camera attitude angles uint8 GET_ANGLES_EXT = 3 # content[0-2]: responded IMU roll, pitch, yaw angles in degrees # content[3-5]: responded target roll, pitch, yaw angles in degrees # content[6-8]: responded stator rotor angles in degrees # request commands uint8 REQUEST_RETURN_HEAD = 4 uint8 REQUEST_CENTER_YAW = 5 uint8 REQUEST_LOOK_DOWN = 6 uint8 REQUEST_FOLLOW_YAW_DISABLE = 7 uint8 REQUEST_FOLLOW_YAW_ENABLE = 8 # camera control commands uint8 REQUEST_ZOOM_OUT = 9 uint8 REQUEST_ZOOM_IN = 10 uint8 REQUEST_STOP_ZOOM = 11 uint8 REQUEST_FOCUS_IN = 12 uint8 REQUEST_FOCUS_OUT = 13 uint8 REQUEST_STOP_FOCUS = 14 uint8 REQUEST_ZOOM_DIRECT_POSITION = 15 # params[0]: zoom value within range [MIN_ZOOM_VALUE, MAX_ZOOM_VALUE] uint8 REQUEST_VIDEO_PHOTO_ACTION = 16 # params[0]: 1: take a picture; 2: start recording; 3: stop recording; 4: reverse capture status; # 05: switch to video or photo mode uint8 cmd_id float32[] params --- bool success float32[] content Service Call in Command Line ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The service can be called in the command line form. Users have to start the driver first: :: cd ~/src/catkinws_periph bash run_campod.sh Then users can start a new terminal, and source the environment of the catkinws_periph as well :: source ~/src/catkinws_periph/devel/setup.bash # request to set yaw target as 90 deg for the camera pod rosservice call /camera_pod_command "cmd_id: 1 params: [0.0, 0.0, 1.0, 0.0, 0.0, 90.0]" Users are advised to use the tab key to fill the service command automatically in the terminal. Success message will be returned if the service call succeeds, as shown below: .. image:: ../img/campod/cam_servicecall.png :height: 400 px :width: 750 px :scale: 100 % :align: center Service Call in Another ROS Package ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ To utilize the service in another ros package, users can either copy the campod_driver package to the same workspace, or source the catkinws_periph workspace before building the new workspace for application. Package dependency has to be specified in the new ROS package, and the service header should be included as well. Since the service server is provided in the camera pod driver, users can simply write a client following the `official ROS tutorial `_, with a form like below: :: ros::NodeHandle n; ros::ServiceClient client = n.serviceClient("camera_pod_command"); camera_pod::Campodcmd srv; srv.request.cmd_id = 1; srv.request.params = [0.0, 0.0, 1.0, 0.0, 0.0, 90.0]; client.call(srv);