diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index c1d129245a..9e28146c3b 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -284,6 +284,9 @@ void Copter::fast_loop() // check if we've landed or crashed update_land_and_crash_detectors(); + // camera mount's fast update + camera_mount.update_fast(); + // log sensor health if (should_log(MASK_LOG_ANY)) { Log_Sensor_Health(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d7d1103f99..b522de067f 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1056,6 +1056,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } + case MAVLINK_MSG_ID_PARAM_VALUE: + { + copter.camera_mount.handle_param_value(msg); + break; + } + case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38 { handle_mission_write_partial_list(copter.mission, msg); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index d8f3fe5a40..963a670c40 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -207,7 +207,7 @@ void Copter::init_ardupilot() #if MOUNT == ENABLED // initialise camera mount - camera_mount.init(serial_manager); + camera_mount.init(&DataFlash, serial_manager); #endif #if PRECISION_LANDING == ENABLED