breezy_board.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef ROSFLIGHT_FIRMWARE_BREEZY_BOARD_H
33 #define ROSFLIGHT_FIRMWARE_BREEZY_BOARD_H
34 
35 #include <cstdbool>
36 #include <cstddef>
37 #include <cstdint>
38 
39 extern "C"
40 {
41 #include <breezystm32.h>
42 }
43 
44 #include "board.h"
45 #include "sensors.h"
46 
47 namespace rosflight_firmware
48 {
49 class BreezyBoard : public Board
50 {
51 private:
53 
54  int _board_revision = 2;
55 
56  float _accel_scale = 1.0;
57  float _gyro_scale = 1.0;
58 
59  enum
60  {
64  };
66 
68  uint32_t pwm_refresh_rate_ = 490;
69  uint16_t pwm_idle_pwm_ = 1000;
70  enum
71  {
75  };
76  uint8_t baro_type = BARO_NONE;
77 
79  uint64_t imu_time_us_;
80 
81 public:
82  BreezyBoard();
83 
84  // setup
85  void init_board() override;
86  void board_reset(bool bootloader) override;
87 
88  // clock
89  uint32_t clock_millis() override;
90  uint64_t clock_micros() override;
91  void clock_delay(uint32_t milliseconds) override;
92 
93  // serial
94  void serial_init(uint32_t baud_rate, uint32_t dev) override;
95  void serial_write(const uint8_t *src, size_t len) override;
96  uint16_t serial_bytes_available() override;
97  uint8_t serial_read() override;
98  void serial_flush() override;
99 
100  // sensors
101  void sensors_init() override;
102  uint16_t num_sensor_errors() override;
103 
104  bool new_imu_data() override;
105  bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time_us) override;
106  void imu_not_responding_error() override;
107 
108  bool mag_present() override;
109  void mag_update() override;
110  void mag_read(float mag[3]) override;
111 
112  bool baro_present() override;
113  void baro_update() override;
114  void baro_read(float *pressure, float *temperature) override;
115 
116  bool diff_pressure_present() override;
117  void diff_pressure_update() override;
118  void diff_pressure_read(float *diff_pressure, float *temperature) override;
119 
120  bool sonar_present() override;
121  void sonar_update() override;
122  float sonar_read() override;
123 
124  bool gnss_present() override { return false; }
125 
126  void gnss_update() override { return; }
127  bool battery_voltage_present() const override;
128  float battery_voltage_read() const override;
129  void battery_voltage_set_multiplier(double multiplier) override;
130 
131  bool battery_current_present() const override;
132  float battery_current_read() const override;
133  void battery_current_set_multiplier(double multiplier) override;
134 
135  GNSSData gnss_read() override;
136  bool gnss_has_new_data() override;
137  GNSSFull gnss_full_read() override;
138 
139  // PWM
140  // TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific)
141  void rc_init(rc_type_t rc_type) override;
142  bool rc_lost() override;
143  float rc_read(uint8_t channel) override;
144 
145  void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override;
146  void pwm_disable() override;
147  void pwm_write(uint8_t channel, float value) override;
148 
149  // non-volatile memory
150  void memory_init() override;
151  bool memory_read(void *dest, size_t len) override;
152  bool memory_write(const void *src, size_t len) override;
153 
154  // LEDs
155  void led0_on() override;
156  void led0_off() override;
157  void led0_toggle() override;
158 
159  void led1_on() override;
160  void led1_off() override;
161  void led1_toggle() override;
162 
163  // Backup Data
164  void backup_memory_init() override {}
165  bool backup_memory_read(void *dest, size_t len) override
166  {
167  (void)dest;
168  (void)len;
169  return false;
170  }
171  void backup_memory_write(const void *src, size_t len) override
172  {
173  (void)src;
174  (void)len;
175  }
176  void backup_memory_clear(size_t len) override { (void)len; }
177 };
178 
179 } // namespace rosflight_firmware
180 
181 #endif // ROSFLIGHT_FIRMWARE_BREEZY_BOARD_H
void pwm_write(uint8_t channel, float value) override
uint16_t serial_bytes_available() override
static volatile int16_t gyro[3]
Definition: drv_mpu6050.c:277
void serial_init(uint32_t baud_rate, uint32_t dev) override
float pressure
Definition: ms4525.c:41
void battery_current_set_multiplier(double multiplier) override
float temperature
Definition: ms4525.c:41
bool memory_read(void *dest, size_t len) override
void backup_memory_write(const void *src, size_t len) override
Definition: breezy_board.h:171
void backup_memory_init() override
Definition: breezy_board.h:164
float battery_current_read() const override
bool battery_current_present() const override
void diff_pressure_read(float *diff_pressure, float *temperature) override
static volatile int16_t accel[3]
Definition: drv_mpu6050.c:276
GNSSFull gnss_full_read() override
void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override
bool memory_write(const void *src, size_t len) override
void board_reset(bool bootloader) override
float rc_read(uint8_t channel) override
bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time_us) override
void backup_memory_clear(size_t len) override
Definition: breezy_board.h:176
void clock_delay(uint32_t milliseconds) override
void imu_not_responding_error() override
void battery_voltage_set_multiplier(double multiplier) override
void baro_read(float *pressure, float *temperature) override
uint32_t clock_millis() override
uint16_t num_sensor_errors() override
bool battery_voltage_present() const override
uint64_t clock_micros() override
void serial_write(const uint8_t *src, size_t len) override
bool backup_memory_read(void *dest, size_t len) override
Definition: breezy_board.h:165
void mag_read(float mag[3]) override
float battery_voltage_read() const override
void rc_init(rc_type_t rc_type) override


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46