|
|
|
@ -1118,35 +1118,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1118,35 +1118,6 @@ void GCS_MAVLINK_Plane::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; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: |
|
|
|
|
plane.camera.set_trigger_distance(packet.param1); |
|
|
|
|
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); |
|
|
|
@ -1665,21 +1636,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1665,21 +1636,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#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); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
#endif // CAMERA == ENABLED
|
|
|
|
|
|
|
|
|
|
#if MOUNT == ENABLED |
|
|
|
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
|
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONFIGURE: |
|
|
|
@ -2001,6 +1957,15 @@ AP_GPS *GCS_MAVLINK_Plane::get_gps() const
@@ -2001,6 +1957,15 @@ AP_GPS *GCS_MAVLINK_Plane::get_gps() const
|
|
|
|
|
return &plane.gps; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_Camera *GCS_MAVLINK_Plane::get_camera() const |
|
|
|
|
{ |
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
return &plane.camera; |
|
|
|
|
#else |
|
|
|
|
return nullptr; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_ServoRelayEvents *GCS_MAVLINK_Plane::get_servorelayevents() const |
|
|
|
|
{ |
|
|
|
|
return &plane.ServoRelayEvents; |
|
|
|
|