Copter: move common mavlink camera handling up
This commit is contained in:
parent
1cb6962f84
commit
f56c9bd96d
@ -1062,35 +1062,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
copter.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:
|
||||
copter.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:
|
||||
copter.camera.set_trigger_distance(packet.param1);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
#endif // CAMERA == ENABLED
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
#if MOUNT == ENABLED
|
||||
copter.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
|
||||
@ -1695,17 +1666,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
#endif // AC_FENCE == ENABLED
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202
|
||||
break;
|
||||
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
||||
copter.camera.control_msg(msg);
|
||||
break;
|
||||
#endif // CAMERA == ENABLED
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
||||
case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // MAV ID: 204
|
||||
@ -1862,6 +1822,15 @@ AP_GPS *GCS_MAVLINK_Copter::get_gps() const
|
||||
return &copter.gps;
|
||||
}
|
||||
|
||||
AP_Camera *GCS_MAVLINK_Copter::get_camera() const
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
return &copter.camera;
|
||||
#else
|
||||
return nullptr;
|
||||
#endif
|
||||
}
|
||||
|
||||
AP_ServoRelayEvents *GCS_MAVLINK_Copter::get_servorelayevents() const
|
||||
{
|
||||
return &copter.ServoRelayEvents;
|
||||
|
@ -21,6 +21,7 @@ protected:
|
||||
AP_Mission *get_mission() override;
|
||||
AP_Rally *get_rally() const override;
|
||||
Compass *get_compass() const override;
|
||||
AP_Camera *get_camera() const override;
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
AP_GPS *get_gps() const override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user