|
|
|
@ -1161,6 +1161,31 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1161,6 +1161,31 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONFIGURE: |
|
|
|
|
plane.camera.configure(packet.param1, |
|
|
|
|
packet.param2, |
|
|
|
|
packet.param3, |
|
|
|
|
packet.param4, |
|
|
|
|
packet.param5, |
|
|
|
|
packet.param6, |
|
|
|
|
packet.param7); |
|
|
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONTROL: |
|
|
|
|
plane.camera.control(packet.param1, |
|
|
|
|
packet.param2, |
|
|
|
|
packet.param3, |
|
|
|
|
packet.param4, |
|
|
|
|
packet.param5, |
|
|
|
|
packet.param6); |
|
|
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
break; |
|
|
|
|
#endif // CAMERA == ENABLED
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_MOUNT_CONTROL: |
|
|
|
|
#if MOUNT == ENABLED |
|
|
|
|
plane.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7); |
|
|
|
@ -1714,11 +1739,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1714,11 +1739,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: |
|
|
|
|
{ |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
|
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONTROL: |
|
|
|
|
{ |
|
|
|
|
plane.camera.control_msg(msg); |
|
|
|
@ -1728,12 +1755,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1728,12 +1755,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
#endif // CAMERA == ENABLED
|
|
|
|
|
|
|
|
|
|
#if MOUNT == ENABLED |
|
|
|
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
|
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONFIGURE: |
|
|
|
|
{ |
|
|
|
|
plane.camera_mount.configure_msg(msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
|
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONTROL: |
|
|
|
|
{ |
|
|
|
|
plane.camera_mount.control_msg(msg); |
|
|
|
|