mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
Copter: make AP_Mount calls required by AP_Mount_SoloGimbal
This commit is contained in:
parent
5b834330cb
commit
22c3397657
@ -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();
|
||||
|
@ -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);
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user