PX4 Firmware
PX4 Autopilot Software http://px4.io
led.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file led.h
36  *
37  * Led controller helper class, used by Led drivers
38  *
39  * @author Beat Küng <beat-kueng@gmx.net>
40  */
41 
42 #pragma once
43 
44 #include <drivers/drv_hrt.h>
45 #include <drivers/drv_led.h>
46 
47 #include <uORB/Subscription.hpp>
49 
51  uint8_t color; ///< one of led_control_s::COLOR_*
52  uint8_t brightness; ///< brightness in [0, 255]
53 };
56 };
57 
58 
59 /**
60  ** class LedController
61  * Handles the led_control topic: blinking, priorities and state updates.
62  */
64 {
65 public:
66  LedController() = default;
67  ~LedController() = default;
68 
69  /**
70  * get maxium time between two consecutive calls to update() in us.
71  */
73  {
74  return _breathe_enabled ? BREATHE_INTERVAL : BLINK_FAST_DURATION;
75  }
76 
77  /**
78  * Update and retrieve the Led state. It will do the orb_copy() and needs to be called at least every
79  * maximum_update_interval(). In addition a caller might poll on the led_control_sub
80  * @param control_data output structure (will always be set)
81  * @return 1 if control_data set (state changed), 0 if control_data not changed (state did not change), <0 error otherwise
82  */
83  int update(LedControlData &control_data);
84 
85  static constexpr int BREATHE_INTERVAL = 25 * 1000; /**< single step when in breathe mode */
86  static constexpr int BREATHE_STEPS = 64; /**< number of steps in breathe mode for a full on-off cycle */
87 
88  static constexpr int BLINK_FAST_DURATION = 100 * 1000; /**< duration of half a blinking cycle
89  (on-to-off and off-to-on) in us */
90  static constexpr int BLINK_NORMAL_DURATION = 500 * 1000; /**< duration of half a blinking cycle
91  (on-to-off and off-to-on) in us */
92  static constexpr int BLINK_SLOW_DURATION = 2000 * 1000; /**< duration of half a blinking cycle
93  (on-to-off and off-to-on) in us */
94 
95 private:
96 
97  /** set control_data based on current Led states */
98  inline void get_control_data(LedControlData &control_data);
99 
101  uint8_t color = 0; ///< one of led_control_s::COLOR_*
102  uint8_t mode = led_control_s::MODE_DISABLED; ///< one of led_control_s::MODE_*
103  uint8_t blink_times_left = 0; /**< how many times left to blink (MSB bit is used for infinite case).
104  This limits the number of complete blink cycles to 64 (if not infinite) */
105  };
106 
107  struct NextState {
108  uint8_t color;
109  uint8_t mode;
110  uint8_t num_blinks;
111  uint8_t priority = led_control_s::MAX_PRIORITY + 1;
112 
113  void set(const led_control_s &led_control)
114  {
115  color = led_control.color;
116  mode = led_control.mode;
117  num_blinks = led_control.num_blinks;
118  priority = led_control.priority;
119 
120  if (priority > led_control_s::MAX_PRIORITY) {
121  priority = led_control_s::MAX_PRIORITY;
122  }
123  }
124  void reset() { priority = led_control_s::MAX_PRIORITY + 1; }
125  bool is_valid() const { return priority != led_control_s::MAX_PRIORITY + 1; }
126  };
127 
128  struct PerLedData {
129  PerPriorityData priority[led_control_s::MAX_PRIORITY + 1];
130  uint16_t current_blinking_time = 0; ///< how long the Led was in current state (in 0.1 ms, wraps if > 6.5s)
132 
133  void set(const led_control_s &led_control)
134  {
135  int next_priority = (int)led_control.priority;
136  priority[next_priority].color = led_control.color;
137  priority[next_priority].mode = led_control.mode;
138 
139  // initialise the flash counter
140  if (led_control.mode == led_control_s::MODE_FLASH) {
141  priority[next_priority].blink_times_left = led_control.num_blinks * 10;
142 
143  } else {
144  priority[next_priority].blink_times_left = led_control.num_blinks * 2;
145  }
146 
147  if (priority[next_priority].blink_times_left == 0) {
148  // handle infinite case
149  priority[next_priority].blink_times_left = 246;
150  }
151 
152 
153  }
154 
156  {
157  int next_priority = (int)next_state.priority;
158  priority[next_priority].color = next_state.color;
159  priority[next_priority].mode = next_state.mode;
160 
161  if (next_state.mode == led_control_s::MODE_FLASH) {
162  priority[next_priority].blink_times_left = next_state.num_blinks * 10;
163 
164  } else {
165  priority[next_priority].blink_times_left = next_state.num_blinks * 2;
166  }
167 
168  if (priority[next_priority].blink_times_left == 0) {
169  // handle infinite case
170  priority[next_priority].blink_times_left = 254;
171  }
172  }
173  };
174 
175  PerLedData _states[BOARD_MAX_LEDS]; ///< keep current LED states
176 
177  uORB::Subscription _led_control_sub{ORB_ID(led_control)}; ///< uorb subscription
178  hrt_abstime _last_update_call{0};
179  bool _force_update{true}; ///< force an orb_copy in the beginning
180  bool _breathe_enabled{false}; ///< true if at least one of the led's is currently in breathe mode
181 };
uint8_t num_blinks
Definition: led.h:110
uint8_t priority
Definition: led_control.h:77
uint8_t color
one of led_control_s::COLOR_*
Definition: led.h:101
static led_control_s led_control
int maximum_update_interval() const
get maxium time between two consecutive calls to update() in us.
Definition: led.h:72
uint8_t color
Definition: led_control.h:74
High-resolution timer with callouts and timekeeping.
uint8_t brightness
brightness in [0, 255]
Definition: led.h:52
uint8_t color
one of led_control_s::COLOR_*
Definition: led.h:51
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
uint8_t mode
Definition: led_control.h:75
Led device API to control the external LED(s) via uORB interface.
void apply_next_state()
Definition: led.h:155
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define BOARD_MAX_LEDS
Definition: drv_led.h:49
uint8_t num_blinks
Definition: led_control.h:76
bool is_valid() const
Definition: led.h:125
uint8_t blink_times_left
how many times left to blink (MSB bit is used for infinite case).
Definition: led.h:103
uint8_t mode
one of led_control_s::MODE_*
Definition: led.h:102
NextState next_state
Definition: led.h:131
mode
Definition: vtol_type.h:76
class LedController Handles the led_control topic: blinking, priorities and state updates...
Definition: led.h:63