123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168 |
- #include "AP_Button.h"
- #include <GCS_MAVLink/GCS_MAVLink.h>
- #include <GCS_MAVLink/GCS.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_Button::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Button, enable, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
- AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1),
-
-
-
-
-
- AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1),
-
-
-
-
-
- AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1),
-
-
-
-
-
- AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1),
-
-
-
-
-
- AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10),
- AP_GROUPEND
- };
- AP_Button::AP_Button(void)
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- void AP_Button::update(void)
- {
- if (!enable) {
- return;
- }
-
- setup_pins();
- if (!initialised) {
- initialised = true;
-
- last_mask = get_mask();
-
- hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));
- }
- if (last_change_time_ms != 0 &&
- (AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS &&
- (AP_HAL::millis64() - last_change_time_ms) < report_send_time*1000ULL) {
-
- last_report_ms = AP_HAL::millis();
-
- send_report();
- }
- }
- uint8_t AP_Button::get_mask(void)
- {
- uint8_t mask = 0;
- for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
- if (pin[i] == -1) {
- continue;
- }
- mask |= hal.gpio->read(pin[i]) << i;
- }
- return mask;
- }
- void AP_Button::timer_update(void)
- {
- if (!enable) {
- return;
- }
- uint8_t mask = get_mask();
- if (mask != last_mask) {
- last_mask = mask;
- last_change_time_ms = AP_HAL::millis64();
- }
- }
- void AP_Button::send_report(void)
- {
- const mavlink_button_change_t packet{
- time_boot_ms: AP_HAL::millis(),
- last_change_ms: uint32_t(last_change_time_ms),
- state: last_mask
- };
- gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,
- (const char *)&packet);
- }
- void AP_Button::setup_pins(void)
- {
- for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
- if (pin[i] == -1) {
- continue;
- }
- hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT);
-
- hal.gpio->write(pin[i], 1);
- }
- }
|