Copter: make AP_Mount calls required by AP_Mount_SoloGimbal

This commit is contained in:
Jonathan Challinger 2016-01-04 21:20:48 -08:00 committed by Randy Mackay
parent 5b834330cb
commit 22c3397657
3 changed files with 10 additions and 1 deletions

View File

@ -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();

View File

@ -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);

View File

@ -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