|
|
@ -686,11 +686,6 @@ static AP_HAL::AnalogSource* rssi_analog_source; |
|
|
|
static AP_Mount camera_mount(¤t_loc, ahrs, 0); |
|
|
|
static AP_Mount camera_mount(¤t_loc, ahrs, 0); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
#if MOUNT2 == ENABLED |
|
|
|
|
|
|
|
// current_loc uses the baro/gps soloution for altitude rather than gps only. |
|
|
|
|
|
|
|
static AP_Mount camera_mount2(¤t_loc, ahrs, 1); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////// |
|
|
|
//////////////////////////////////////////////////////////////////////////////// |
|
|
|
// AC_Fence library to reduce fly-aways |
|
|
|
// AC_Fence library to reduce fly-aways |
|
|
|
//////////////////////////////////////////////////////////////////////////////// |
|
|
|
//////////////////////////////////////////////////////////////////////////////// |
|
|
@ -1043,11 +1038,6 @@ static void update_mount() |
|
|
|
camera_mount.update_mount_position(); |
|
|
|
camera_mount.update_mount_position(); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
#if MOUNT2 == ENABLED |
|
|
|
|
|
|
|
// update camera mount's position |
|
|
|
|
|
|
|
camera_mount2.update_mount_position(); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
#if CAMERA == ENABLED |
|
|
|
camera.trigger_pic_cleanup(); |
|
|
|
camera.trigger_pic_cleanup(); |
|
|
|
#endif |
|
|
|
#endif |
|
|
@ -1168,10 +1158,6 @@ static void one_hz_loop() |
|
|
|
camera_mount.update_mount_type(); |
|
|
|
camera_mount.update_mount_type(); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
#if MOUNT2 == ENABLED |
|
|
|
|
|
|
|
camera_mount2.update_mount_type(); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
check_usb_mux(); |
|
|
|
check_usb_mux(); |
|
|
|
|
|
|
|
|
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|