Add an optional second mount to ArduPlane and ArduCopter
This commit is contained in:
parent
0b0b9c29a2
commit
d34549f386
@ -333,7 +333,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// @Group: MNT_
|
||||
// @Group: MNT2_
|
||||
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
||||
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
|
||||
#endif
|
||||
|
@ -486,11 +486,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef MOUNT2
|
||||
# if defined( __AVR_ATmega1280__ )
|
||||
# define MOUNT2 DISABLED
|
||||
# else
|
||||
# define MOUNT2 ENABLED
|
||||
# endif
|
||||
# define MOUNT2 DISABLED
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
|
||||
|
@ -665,7 +665,13 @@ static float load;
|
||||
#if MOUNT == ENABLED
|
||||
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
||||
// mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
|
||||
AP_Mount camera_mount(¤t_loc, g_gps, &ahrs);
|
||||
AP_Mount camera_mount(¤t_loc, g_gps, &ahrs, 0);
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
||||
// mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
|
||||
AP_Mount camera_mount2(¤t_loc, g_gps, &ahrs, 1);
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
@ -798,6 +804,10 @@ static void medium_loop()
|
||||
camera_mount.update_mount_position();
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
camera_mount2.update_mount_position();
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
g.camera.trigger_pic_cleanup();
|
||||
#endif
|
||||
@ -941,6 +951,9 @@ static void slow_loop()
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
camera_mount.update_mount_type();
|
||||
#endif
|
||||
#if MOUNT2 == ENABLED
|
||||
camera_mount2.update_mount_type();
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -121,6 +121,7 @@ public:
|
||||
//
|
||||
k_param_camera = 160,
|
||||
k_param_camera_mount,
|
||||
k_param_camera_mount2,
|
||||
|
||||
//
|
||||
// 170: Radio settings
|
||||
|
@ -539,6 +539,11 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(camera_mount, "MNT_", AP_Mount),
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// @Group: MNT2_
|
||||
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
||||
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
|
||||
#endif
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
// @Group: SIM_
|
||||
|
@ -460,7 +460,11 @@
|
||||
# define MOUNT ENABLED
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED)
|
||||
#ifndef MOUNT2
|
||||
# define MOUNT2 DISABLED
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
|
||||
|
||||
// The small ATmega1280 chip does not have enough memory for mount support
|
||||
// so disable CLI, this will allow mount support and other improvements to fit.
|
||||
|
Loading…
Reference in New Issue
Block a user