Browse Source

Copter: allow mount to be disabled

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
27ed9e1561
  1. 2
      ArduCopter/ArduCopter.cpp
  2. 2
      ArduCopter/GCS_Mavlink.cpp

2
ArduCopter/ArduCopter.cpp

@ -284,8 +284,10 @@ void Copter::fast_loop()
// check if we've landed or crashed // check if we've landed or crashed
update_land_and_crash_detectors(); update_land_and_crash_detectors();
#if MOUNT == ENABLED
// camera mount's fast update // camera mount's fast update
camera_mount.update_fast(); camera_mount.update_fast();
#endif
// log sensor health // log sensor health
if (should_log(MASK_LOG_ANY)) { if (should_log(MASK_LOG_ANY)) {

2
ArduCopter/GCS_Mavlink.cpp

@ -1058,7 +1058,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_VALUE: case MAVLINK_MSG_ID_PARAM_VALUE:
{ {
#if MOUNT == ENABLED
copter.camera_mount.handle_param_value(msg); copter.camera_mount.handle_param_value(msg);
#endif
break; break;
} }

Loading…
Cancel
Save