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_BOARD_H
33 #define ROSFLIGHT_FIRMWARE_BOARD_H
34 
35 #include <functional>
36 #include <stddef.h>
37 #include <stdbool.h>
38 #include <stdint.h>
39 
40 #include "sensors.h"
41 #include "state_manager.h"
42 
43 namespace rosflight_firmware
44 {
46 {
47  uint32_t r0;
48  uint32_t r1;
49  uint32_t r2;
50  uint32_t r3;
51  uint32_t r12;
52  uint32_t lr;
53  uint32_t pc;
54  uint32_t psr;
55 };
56 struct BackupData
57 {
58  uint32_t error_code;
60  uint32_t reset_count;
61  uint32_t arm_status; //This must equals ARM_MAGIC, or else the state manager will not rearm on reboot
62  //TODO add state manager info
64  uint32_t checksum; //With the current implementation of the checksum, this must go last
65 };
66 //This magic number is used to check that the firmware was armed before it reset
67 const uint32_t ARM_MAGIC = 0xfa11bad;
68 
69 class Board
70 {
71 
72 public:
73  typedef enum
74  {
75  RC_TYPE_PPM = 0,
76  RC_TYPE_SBUS = 1
77  } rc_type_t;
78 
79 // setup
80  virtual void init_board() = 0;
81  virtual void board_reset(bool bootloader) = 0;
82 
83 // clock
84  virtual uint32_t clock_millis() = 0;
85  virtual uint64_t clock_micros() = 0;
86  virtual void clock_delay(uint32_t milliseconds) = 0;
87 
88 // serial
89  virtual void serial_init(uint32_t baud_rate, uint32_t dev) = 0;
90  virtual void serial_write(const uint8_t *src, size_t len) = 0;
91  virtual uint16_t serial_bytes_available() = 0;
92  virtual uint8_t serial_read() = 0;
93  virtual void serial_flush() = 0;
94 
95 // sensors
96  virtual void sensors_init() = 0;
97  virtual uint16_t num_sensor_errors() = 0;
98 
99  virtual bool new_imu_data() = 0;
100  virtual bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time) = 0;
101  virtual void imu_not_responding_error() = 0;
102 
103  virtual bool mag_present() = 0;
104  virtual void mag_update() = 0;
105  virtual void mag_read(float mag[3]) = 0;
106 
107  virtual bool baro_present() = 0;
108  virtual void baro_update() = 0;
109  virtual void baro_read(float *pressure, float *temperature) = 0;
110 
111  virtual bool diff_pressure_present() = 0;
112  virtual void diff_pressure_update() = 0;
113  virtual void diff_pressure_read(float *diff_pressure, float *temperature) = 0;
114 
115  virtual bool sonar_present() = 0;
116  virtual void sonar_update() = 0;
117  virtual float sonar_read() = 0;
118 
119  virtual bool gnss_present() = 0;
120  virtual void gnss_update() = 0;
121 
122  virtual GNSSData gnss_read() = 0;
123  virtual bool gnss_has_new_data() = 0;
124  virtual GNSSRaw gnss_raw_read() = 0;
125 
126 // RC
127  virtual void rc_init(rc_type_t rc_type) = 0;
128  virtual bool rc_lost() = 0;
129  virtual float rc_read(uint8_t channel) = 0;
130 
131 // PWM
132  virtual void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) = 0;
133  virtual void pwm_disable() = 0;
134  virtual void pwm_write(uint8_t channel, float value) = 0;
135 
136 // non-volatile memory
137  virtual void memory_init() = 0;
138  virtual bool memory_read(void *dest, size_t len) = 0;
139  virtual bool memory_write(const void *src, size_t len) = 0;
140 
141 // LEDs
142  virtual void led0_on() = 0;
143  virtual void led0_off() = 0;
144  virtual void led0_toggle() = 0;
145 
146  virtual void led1_on() = 0;
147  virtual void led1_off() = 0;
148  virtual void led1_toggle() = 0;
149 
150 // Backup memory
151  virtual bool has_backup_data() = 0;
152  virtual BackupData get_backup_data() = 0;
153 
154 };
155 
156 } // namespace rosflight_firmware
157 
158 #endif // ROSLFIGHT_FIRMWARE_BOARD_H
static volatile int16_t gyro[3]
Definition: drv_mpu6050.c:277
float pressure
Definition: ms4525.c:41
debug_info_t debug_info
Definition: board.h:59
float temperature
Definition: ms4525.c:41
static bool new_imu_data
Definition: drv_mpu6050.c:95
bool sonar_present
Definition: multisense.c:44
static volatile int16_t accel[3]
Definition: drv_mpu6050.c:276
StateManager::State state
Definition: board.h:63
bool baro_present
Definition: multisense.c:42
uint16_t num_sensor_errors()
const uint32_t ARM_MAGIC
Definition: board.h:67
bool mag_present
Definition: multisense.c:43


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