吊舱操作
注意:本教程仅适用于配备吊舱的Kerloud 600无人机。
吊舱是无人机在航空测绘、视频/图像监控、视觉跟踪和定位应用场景下的常见设备。我们为用户提供简化视频监控、处理的高级选项, Kerloud 600 Pro-Cam Pod, 该款型可用作室外监控应用开发的基点。借助已有软件环境,用户可以轻松构建自己的应用程序,例如视频传输以及使用深度学习神经网络的实时视觉识别。本教程中我们将说明如何访问机载视觉,以及如何在 ROS 环境中操作吊舱。
视频和图像采集
Kerloud 600 Pro-Cam Pod 中的默认相机单元支持 1080P 60fps 视频流和 10 倍光学变焦。该参数使无人机能够识别1000米内的汽车,如下图所示:
我们已准备好软件环境供用户获取板载视频流和图像。要从吊舱查看实时视频,请运行以下命令:
cd ~/src/catkinws_periph
bash view_campod_video.sh
视频将显示如下:
要在ROS环境下发布在线镜像,运行命令:
cd ~/src/catkinws_periph
bash pub_campod_image.sh
图像主题可通过 rqt_image_view 命令查看:
吊舱动作指令
服务详情
默认吊舱支持的用户操作包含相机姿态命令、缩放、聚焦、视频捕获和照片拍摄。这些操作是通过路径**~/src/catkinws_periph/src/campod_driver**下提供的ROS 驱动程序的服务来实现的。 下面列出了服务的详细信息,在此强烈建议用户参考驱动程序包中的 README 文件以保持最新版本。
# 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
命令行中的服务调用
该服务可以通过命令行形式调用。用户必须先启动驱动程序:
cd ~/src/catkinws_periph
bash run_campod.sh
然后用户可以启动一个新的终端,并获取catkinws_periph的环境:
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]"
建议用户在终端使用 tab 键自动填写服务命令。若服务调用成功会返回成功信息,如下图:
ROS包中的服务调用
若要在另一个 ros 包中使用该服务,用户可将 campod_driver 包复制到同一工作区,或者在为应用程序构建新工作区之前获取 catkinws_periph 工作区。在新的 ROS 包中必须指定包依赖性,且应包含服务头。
由于吊舱驱动中提供了服务服务器,用户可以简单的按照 ROS官方教程 写一个客户端,形式如下:
ros::NodeHandle n;
ros::ServiceClient client = n.serviceClient<camera_pod::Campodcmd>("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);