Copter: integrate Precision Landing lib

This commit is contained in:
Randy Mackay 2015-02-16 13:39:18 +09:00
parent 5a4729a966
commit 26ded641db
9 changed files with 62 additions and 0 deletions

View File

@ -36,6 +36,7 @@
// features below are disabled by default on all boards
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define PRECISION_LANDING ENABLED // enable precision landing using companion computer or IRLock sensor
// other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)

View File

@ -110,6 +110,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = {
{ SCHED_TASK(three_hz_loop), 133, 75 },
{ SCHED_TASK(compass_accumulate), 8, 100 },
{ SCHED_TASK(barometer_accumulate), 8, 90 },
#if PRECISION_LANDING == ENABLED
{ SCHED_TASK(update_precland), 8, 50 },
#endif
#if FRAME_CONFIG == HELI_FRAME
{ SCHED_TASK(check_dynamic_flight), 8, 75 },
#endif

View File

@ -119,6 +119,9 @@ Copter::Copter(void) :
#endif
#if AP_TERRAIN_AVAILABLE
terrain(ahrs, mission, rally),
#endif
#if PRECISION_LANDING == ENABLED
precland(ahrs, inertial_nav, g.pi_precland, MAIN_LOOP_SECONDS),
#endif
in_mavlink_delay(false),
gcs_out_of_time(false),

View File

@ -108,6 +108,10 @@
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RPM/AP_RPM.h>
#if PRECISION_LANDING == ENABLED
#include <AC_PrecLand/AC_PrecLand.h>
#include <AP_IRLock/AP_IRLock.h>
#endif
// AP_HAL to Arduino compatibility layer
// Configuration
@ -494,6 +498,11 @@ private:
AP_Terrain terrain;
#endif
// Precision Landing
#if PRECISION_LANDING == ENABLED
AC_PrecLand precland;
#endif
// use this to prevent recursion during sensor init
bool in_mavlink_delay;
@ -867,6 +876,8 @@ private:
void init_compass();
void init_optflow();
void update_optical_flow(void);
void init_precland();
void update_precland();
void read_battery(void);
void read_receiver_rssi(void);
void epm_update();

View File

@ -1058,6 +1058,12 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
GOBJECT(optflow, "FLOW", OpticalFlow),
#endif
#if PRECISION_LANDING == ENABLED
// @Group: PRECLAND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
GOBJECT(precland, "PLAND_", AC_PrecLand),
#endif
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),

View File

@ -82,6 +82,9 @@ public:
// Landing gear object
k_param_landinggear, // 18
// precision landing object
k_param_precland, // 19
// Misc
//
k_param_log_bitmask_old = 20, // Deprecated

View File

@ -330,6 +330,12 @@
# define SPRAYER DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Precision Landing with companion computer or IRLock sensor
#ifndef PRECISION_LANDING
# define PRECISION_LANDING DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// EPM cargo gripper
#ifndef EPM_ENABLED

View File

@ -0,0 +1,24 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// functions to support precision landing
//
#include "Copter.h"
#if PRECISION_LANDING == ENABLED
void Copter::init_precland()
{
copter.precland.init();
}
void Copter::update_precland()
{
copter.precland.update(current_loc.alt);
// log output
Log_Write_Precland();
}
#endif

View File

@ -203,6 +203,11 @@ void Copter::init_ardupilot()
camera_mount.init(serial_manager);
#endif
#if PRECISION_LANDING == ENABLED
// initialise precision landing
init_precland();
#endif
#ifdef USERHOOK_INIT
USERHOOK_INIT
#endif