mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Add a second mount instance
This commit is contained in:
parent
530ea0bebd
commit
9cc705939a
@ -963,6 +963,12 @@ AP_Relay relay;
|
||||
AP_Mount camera_mount(¤t_loc, g_gps, &ahrs);
|
||||
#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);
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
//pinMode(camtrig, OUTPUT); // these are free pins PE3(5), PH3(15), PH6(18), PB4(23), PB5(24), PL1(36), PL3(38), PA6(72), PA7(71), PK0(89), PK1(88), PK2(87), PK3(86), PK4(83), PK5(84), PK6(83), PK7(82)
|
||||
#endif
|
||||
@ -1274,6 +1280,11 @@ static void fifty_hz_loop()
|
||||
camera_mount.update_mount_position();
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// update camera mount's position
|
||||
camera_mount2.update_mount_position();
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
g.camera.trigger_pic_cleanup();
|
||||
#endif
|
||||
@ -1341,6 +1352,10 @@ static void slow_loop()
|
||||
camera_mount.update_mount_type();
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
camera_mount2.update_mount_type();
|
||||
#endif
|
||||
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_SLOWLOOP
|
||||
USERHOOK_SLOWLOOP
|
||||
|
@ -127,6 +127,7 @@ public:
|
||||
//
|
||||
k_param_camera = 165,
|
||||
k_param_camera_mount,
|
||||
k_param_camera_mount2,
|
||||
|
||||
//
|
||||
// 170: Radio settings
|
||||
|
@ -332,6 +332,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(camera_mount, "MNT_", AP_Mount),
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// @Group: MNT_
|
||||
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
||||
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
|
||||
#endif
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
GOBJECT(sitl, "SIM_", SITL),
|
||||
#endif
|
||||
|
@ -485,7 +485,15 @@
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED)
|
||||
#ifndef MOUNT2
|
||||
# if defined( __AVR_ATmega1280__ )
|
||||
# define MOUNT2 DISABLED
|
||||
# else
|
||||
# define MOUNT2 ENABLED
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
|
||||
# warning "You choose to enable MOUNT on a small ATmega1280, CLI, CAMERA and AP_LIMITS will be disabled to free some space for it"
|
||||
|
||||
// The small ATmega1280 chip does not have enough memory for mount support
|
||||
|
Loading…
Reference in New Issue
Block a user