Copter: added AP_Button support

This commit is contained in:
Andrew Tridgell 2016-07-22 11:24:13 +10:00
parent 3f0a8d1761
commit cb5ca713a9
5 changed files with 18 additions and 0 deletions

View File

@ -151,6 +151,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#ifdef USERHOOK_SUPERSLOWLOOP #ifdef USERHOOK_SUPERSLOWLOOP
SCHED_TASK(userhook_SuperSlowLoop, 1, 75), SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
#endif #endif
SCHED_TASK(button_update, 5, 100),
}; };

View File

@ -88,6 +88,7 @@
#include <AP_RPM/AP_RPM.h> #include <AP_RPM/AP_RPM.h>
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library #include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library #include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
#include <AP_Button/AP_Button.h>
// Configuration // Configuration
#include "defines.h" #include "defines.h"
@ -660,6 +661,7 @@ private:
void send_rangefinder(mavlink_channel_t chan); void send_rangefinder(mavlink_channel_t chan);
void send_rpm(mavlink_channel_t chan); void send_rpm(mavlink_channel_t chan);
void rpm_update(); void rpm_update();
void button_update();
void send_pid_tuning(mavlink_channel_t chan); void send_pid_tuning(mavlink_channel_t chan);
void gcs_send_message(enum ap_message id); void gcs_send_message(enum ap_message id);
void gcs_send_mission_item_reached_message(uint16_t mission_index); void gcs_send_mission_item_reached_message(uint16_t mission_index);

View File

@ -966,6 +966,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("WP_TKOFF_NAV_ALT", 1, ParametersG2, takeoff_nav_alt, 0), AP_GROUPINFO("WP_TKOFF_NAV_ALT", 1, ParametersG2, takeoff_nav_alt, 0),
// @Group: BTN_
// @Path: ../libraries/AP_Button/AP_Button.cpp
AP_SUBGROUPINFO(button, "BTN_", 2, ParametersG2, AP_Button),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -543,6 +543,9 @@ public:
// altitude at which nav control can start in takeoff // altitude at which nav control can start in takeoff
AP_Float takeoff_nav_alt; AP_Float takeoff_nav_alt;
// button checking
AP_Button button;
}; };
extern const AP_Param::Info var_info[]; extern const AP_Param::Info var_info[];

View File

@ -226,3 +226,11 @@ void Copter::epm_update()
epm.update(); epm.update();
} }
#endif #endif
/*
update AP_Button
*/
void Copter::button_update(void)
{
g2.button.update();
}