From 077f577e5c69c6aaab68a5b30c636d445ad16aa2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 26 Jul 2017 15:48:15 +1000 Subject: [PATCH] Sub: move common mavlink camera handling up --- ArduSub/GCS_Mavlink.cpp | 47 ++++++++--------------------------------- ArduSub/GCS_Mavlink.h | 1 + 2 files changed, 10 insertions(+), 38 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 1def94cdd2..61729fae0e 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1133,33 +1133,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_ACCEPTED; break; -#if CAMERA == ENABLED - case MAV_CMD_DO_DIGICAM_CONFIGURE: - sub.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: - sub.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: - sub.camera.set_trigger_distance(packet.param1); - result = MAV_RESULT_ACCEPTED; - break; -#endif // CAMERA == ENABLED case MAV_CMD_DO_MOUNT_CONTROL: #if MOUNT == ENABLED sub.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7); @@ -1556,17 +1529,6 @@ void GCS_MAVLINK_Sub::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: - sub.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 @@ -1704,6 +1666,15 @@ AP_GPS *GCS_MAVLINK_Sub::get_gps() const return &sub.gps; } +AP_Camera *GCS_MAVLINK_Sub::get_camera() const +{ +#if CAMERA == ENABLED + return &sub.camera; +#else + return nullptr; +#endif +} + AP_ServoRelayEvents *GCS_MAVLINK_Sub::get_servorelayevents() const { return &sub.ServoRelayEvents; diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 9234ceec1b..25b3510d1c 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -17,6 +17,7 @@ protected: Compass *get_compass() const override; AP_Mission *get_mission() override; AP_Rally *get_rally() const override; + AP_Camera *get_camera() const override; AP_ServoRelayEvents *get_servorelayevents() const override; AP_GPS *get_gps() const override;