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 <stddef.h>
36 #include <stdbool.h>
37 #include <stdint.h>
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 
50 class BreezyBoard : public Board
51 {
52 
53 private:
55 
56  std::function<void(void)> imu_callback_;
57 
58  int _board_revision = 2;
59 
60  float _accel_scale = 1.0;
61  float _gyro_scale = 1.0;
62 
63  enum
64  {
68  };
70 
72  uint32_t pwm_refresh_rate_ = 490;
73  uint16_t pwm_idle_pwm_ = 1000;
74  enum
75  {
79  };
80  uint8_t baro_type = BARO_NONE;
81 
83  uint64_t imu_time_us_;
84 
85 public:
86  BreezyBoard();
87 
88  // setup
89  void init_board() override;
90  void board_reset(bool bootloader) override;
91 
92  // clock
93  uint32_t clock_millis() override;
94  uint64_t clock_micros() override;
95  void clock_delay(uint32_t milliseconds) override;
96 
97  // serial
98  void serial_init(uint32_t baud_rate, uint32_t dev) override;
99  void serial_write(const uint8_t *src, size_t len) override;
100  uint16_t serial_bytes_available() override;
101  uint8_t serial_read() override;
102  void serial_flush() override;
103 
104  // sensors
105  void sensors_init() override;
106  uint16_t num_sensor_errors() override;
107 
108  bool new_imu_data() override;
109  bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time_us) override;
110  void imu_not_responding_error() override;
111 
112  bool mag_present() override;
113  void mag_update() override;
114  void mag_read(float mag[3]) override;
115 
116  bool baro_present() override;
117  void baro_update() override;
118  void baro_read(float *pressure, float *temperature) override;
119 
120  bool diff_pressure_present() override;
121  void diff_pressure_update() override;
122  void diff_pressure_read(float *diff_pressure, float *temperature) override;
123 
124  bool sonar_present() override;
125  void sonar_update() override;
126  float sonar_read() override;
127 
128  bool gnss_present() override
129  {
130  return false;
131  }
132  void gnss_update() override
133  {
134  return;
135  }
136  GNSSData gnss_read() override;
137  bool gnss_has_new_data() override;
138  GNSSRaw gnss_raw_read() override;
139 
140 
141  // PWM
142  // TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific)
143  void rc_init(rc_type_t rc_type) override;
144  bool rc_lost() override;
145  float rc_read(uint8_t channel) override;
146 
147  void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override;
148  void pwm_disable() override;
149  void pwm_write(uint8_t channel, float value) override;
150 
151  // non-volatile memory
152  void memory_init() override;
153  bool memory_read(void *dest, size_t len) override;
154  bool memory_write(const void *src, size_t len) override;
155 
156  // LEDs
157  void led0_on() override;
158  void led0_off() override;
159  void led0_toggle() override;
160 
161  void led1_on() override;
162  void led1_off() override;
163  void led1_toggle() override;
164 
165  // Backup memory
166  bool has_backup_data() override;
167  BackupData get_backup_data() override;
168 };
169 
170 } // namespace rosflight_firmware
171 
172 #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
float temperature
Definition: ms4525.c:41
bool memory_read(void *dest, size_t len) override
GNSSRaw gnss_raw_read() override
void diff_pressure_read(float *diff_pressure, float *temperature) override
static volatile int16_t accel[3]
Definition: drv_mpu6050.c:276
void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override
bool memory_write(const void *src, size_t len) override
BackupData get_backup_data() 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 clock_delay(uint32_t milliseconds) override
void imu_not_responding_error() override
void baro_read(float *pressure, float *temperature) override
uint32_t clock_millis() override
uint16_t num_sensor_errors() override
std::function< void(void)> imu_callback_
Definition: breezy_board.h:56
uint64_t clock_micros() override
void serial_write(const uint8_t *src, size_t len) override
void mag_read(float mag[3]) override
void rc_init(rc_type_t rc_type) override


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24