APM:Libraries
AP_ServoRelayEvents.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  * AP_ServoRelayEvents - handle servo and relay MAVLink events
17  */
18 
19 
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_Common/AP_Common.h>
22 #include "AP_ServoRelayEvents.h"
23 #include <RC_Channel/RC_Channel.h>
25 
26 extern const AP_HAL::HAL& hal;
27 
28 bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
29 {
30  if (!(mask & 1U<<(_channel-1))) {
31  // not allowed
32  return false;
33  }
34  if (type == EVENT_TYPE_SERVO &&
35  channel == _channel) {
36  // cancel previous repeat
37  repeat = 0;
38  }
39  SRV_Channel *c = SRV_Channels::srv_channel(_channel-1);
40  if (c == nullptr) {
41  return false;
42  }
43  c->set_output_pwm(pwm);
44  return true;
45 }
46 
47 bool AP_ServoRelayEvents::do_set_relay(uint8_t relay_num, uint8_t state)
48 {
49  if (!relay.enabled(relay_num)) {
50  return false;
51  }
52  if (type == EVENT_TYPE_RELAY &&
53  channel == relay_num) {
54  // cancel previous repeat
55  repeat = 0;
56  }
57  if (state == 1) {
58  relay.on(relay_num);
59  } else if (state == 0) {
60  relay.off(relay_num);
61  } else {
62  relay.toggle(relay_num);
63  }
64  return true;
65 }
66 
67 bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_value,
68  int16_t _repeat, uint16_t _delay_ms)
69 {
70  if (!(mask & 1U<<(_channel-1))) {
71  // not allowed
72  return false;
73  }
74  channel = _channel;
76 
77  start_time_ms = 0;
78  delay_ms = _delay_ms / 2;
79  repeat = _repeat * 2;
80  servo_value = _servo_value;
81  update_events();
82  return true;
83 }
84 
85 bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, uint32_t _delay_ms)
86 {
87  if (!relay.enabled(relay_num)) {
88  return false;
89  }
91  channel = relay_num;
92  start_time_ms = 0;
93  delay_ms = _delay_ms/2; // half cycle time
94  repeat = _repeat*2; // number of full cycles
95  update_events();
96  return true;
97 }
98 
99 
100 /*
101  update state for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_REPEAT_RELAY
102 */
104 {
105  if (repeat == 0 || (AP_HAL::millis() - start_time_ms) < delay_ms) {
106  return;
107  }
108 
110 
111  switch (type) {
112  case EVENT_TYPE_SERVO: {
114  if (c != nullptr) {
115  if (repeat & 1) {
116  c->set_output_pwm(c->get_trim());
117  } else {
119  }
120  }
121  break;
122  }
123 
124  case EVENT_TYPE_RELAY:
126  break;
127  }
128 
129  if (repeat > 0) {
130  repeat--;
131  } else {
132  // toggle bottom bit so servos flip in value
133  repeat ^= 1;
134  }
135 }
136 
137 // singleton instance
139 
140 namespace AP {
141 
143 {
145 }
146 
147 }
bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms)
AP_ServoRelayEvents * servorelayevents()
bool enabled(uint8_t relay)
Definition: AP_Relay.h:36
bool do_set_servo(uint8_t channel, uint16_t pwm)
void off(uint8_t relay)
Definition: AP_Relay.cpp:127
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms)
static uint16_t pwm
Definition: RCOutput.cpp:20
void on(uint8_t relay)
Definition: AP_Relay.cpp:118
void toggle(uint8_t relay)
Definition: AP_Relay.cpp:136
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
Definition: AP_AHRS.cpp:486
static AP_ServoRelayEvents * get_singleton()
RC_Channel manager, with EEPROM-backed storage of constants.
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
static AP_ServoRelayEvents * _singleton
Common definitions and utility routines for the ArduPilot libraries.
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool do_set_relay(uint8_t relay_num, uint8_t state)
void set_output_pwm(uint16_t pwm)