# 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]"