diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index d086a60038..df0baebad3 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -123,27 +123,6 @@ AP_Camera::trigger_pic_cleanup() } } -/// decode MavLink that configures camera -void -AP_Camera::configure_msg(mavlink_message_t* msg) -{ - __mavlink_digicam_configure_t packet; - mavlink_msg_digicam_configure_decode(msg, &packet); - // This values may or not be used by APM - // They are bypassed as "echo" to a external specialized board - /* - * packet.aperture - * packet.command_id - * packet.engine_cut_off - * packet.exposure_type - * packet.extra_param - * packet.extra_value - * packet.iso - * packet.mode - * packet.shutter_speed - */ -} - /// decode MavLink that controls camera void AP_Camera::control_msg(mavlink_message_t* msg) diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 1a93dbd7a6..afc8f73d40 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -49,7 +49,6 @@ public: void trigger_pic_cleanup(); // MAVLink methods - void configure_msg(mavlink_message_t* msg); void control_msg(mavlink_message_t* msg); void send_feedback(mavlink_channel_t chan, AP_GPS &gps, const AP_AHRS &ahrs, const Location ¤t_loc);