Plane: integrate mount frontend-backend restructure

initialise mount on startup
use mount.has_pan_control method
remove calls to unimplemented mount.configure_cmd
remove call to update_mount_type which is now handled by mount lib
This commit is contained in:
Randy Mackay 2015-01-09 05:12:08 +09:00 committed by Andrew Tridgell
parent 31b2534c1d
commit 681d28838f
7 changed files with 9 additions and 42 deletions

View File

@ -739,13 +739,7 @@ static uint16_t mainLoop_count;
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // 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? // mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
static AP_Mount camera_mount(&current_loc, ahrs, 0); static AP_Mount camera_mount(ahrs, current_loc);
#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?
static AP_Mount camera_mount2(&current_loc, ahrs, 1);
#endif #endif
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
@ -915,11 +909,7 @@ static void update_speed_height(void)
static void update_mount(void) static void update_mount(void)
{ {
#if MOUNT == ENABLED #if MOUNT == ENABLED
camera_mount.update_mount_position(); camera_mount.update();
#endif
#if MOUNT2 == ENABLED
camera_mount2.update_mount_position();
#endif #endif
#if CAMERA == ENABLED #if CAMERA == ENABLED
@ -1010,13 +1000,6 @@ static void update_aux(void)
if (!px4io_override_enabled) { if (!px4io_override_enabled) {
RC_Channel_aux::enable_aux_servos(); RC_Channel_aux::enable_aux_servos();
} }
#if MOUNT == ENABLED
camera_mount.update_mount_type();
#endif
#if MOUNT2 == ENABLED
camera_mount2.update_mount_type();
#endif
} }
static void one_second_loop() static void one_second_loop()

View File

@ -1020,7 +1020,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} }
} else { } else {
// send the command to the camera mount // send the command to the camera mount
camera_mount.set_roi_cmd(&roi_loc); camera_mount.set_roi_target(roi_loc);
} }
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
break; break;

View File

@ -208,7 +208,7 @@ public:
// //
k_param_camera = 160, k_param_camera = 160,
k_param_camera_mount, k_param_camera_mount,
k_param_camera_mount2, k_param_camera_mount2, // unused
// //
// Battery monitoring parameters // Battery monitoring parameters

View File

@ -1112,12 +1112,6 @@ const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(camera_mount, "MNT_", AP_Mount), GOBJECT(camera_mount, "MNT_", AP_Mount),
#endif #endif
#if MOUNT2 == ENABLED
// @Group: MNT2_
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
#endif
// @Group: BATT_ // @Group: BATT_
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT", AP_BattMonitor), GOBJECT(battery, "BATT", AP_BattMonitor),

View File

@ -176,18 +176,10 @@ start_command(const AP_Mission::Mission_Command& cmd)
camera_mount.set_mode_to_default(); camera_mount.set_mode_to_default();
} }
} else { } else {
// send the command to the camera mount // set mount's target location
camera_mount.set_roi_cmd(&cmd.content.location); camera_mount.set_roi_target(cmd.content.location);
} }
break; break;
case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
camera_mount.configure_cmd();
break;
case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
camera_mount.control_cmd();
break;
#endif #endif
} }

View File

@ -282,11 +282,6 @@
# define MOUNT ENABLED # define MOUNT ENABLED
#endif #endif
// second mount, can for example be used to keep an antenna pointed at the home position
#ifndef MOUNT2
# define MOUNT2 DISABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// FLIGHT AND NAVIGATION CONTROL // FLIGHT AND NAVIGATION CONTROL

View File

@ -186,6 +186,9 @@ static void init_ardupilot()
relay.init(); relay.init();
// initialise camera mount
camera_mount.init();
#if FENCE_TRIGGERED_PIN > 0 #if FENCE_TRIGGERED_PIN > 0
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT); hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0); hal.gpio->write(FENCE_TRIGGERED_PIN, 0);