test_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_TEST_BOARD_H
33 #define ROSFLIGHT_FIRMWARE_TEST_BOARD_H
34 
35 #include "board.h"
36 #include "sensors.h"
37 
38 namespace rosflight_firmware
39 {
40 
41 class testBoard : public Board
42 {
43 
44 private:
45  uint16_t rc_values[8] = {0, 0, 0, 0, 0, 0, 0, 0};
46  uint64_t time_us_ = 0;
47  bool rc_lost_ = false;
48  float acc_[3] = {0, 0, 0};
49  float gyro_[3] = {0, 0, 0};
50  bool new_imu_ = false;
51 
52 public:
53 // setup
54  void init_board() override;
55  void board_reset(bool bootloader) override;
56 
57 // clock
58  uint32_t clock_millis() override;
59  uint64_t clock_micros() override;
60  void clock_delay(uint32_t milliseconds) override;
61 
62 // serial
63  void serial_init(uint32_t baud_rate, uint32_t dev) override;
64  void serial_write(const uint8_t *src, size_t len) override;
65  uint16_t serial_bytes_available() override;
66  uint8_t serial_read() override;
67  void serial_flush() override;
68 
69 // sensors
70  void sensors_init() override;
71  uint16_t num_sensor_errors() ;
72 
73  bool new_imu_data() override;
74  bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time) override;
75  void imu_not_responding_error() override;
76 
77  bool mag_present() override;
78  void mag_update() override;
79  void mag_read(float mag[3]) override;
80 
81  bool baro_present() override;
82  void baro_update() override;
83  void baro_read(float *pressure, float *temperature) override;
84 
85  bool diff_pressure_present() override;
86  void diff_pressure_update() override;
87  void diff_pressure_read(float *diff_pressure, float *temperature) override;
88 
89  bool sonar_present() override;
90  void sonar_update() override;
91  float sonar_read() override;
92 
93  bool gnss_present() override
94  {
95  return false;
96  }
97  void gnss_update() override {}
98  GNSSData gnss_read() override;
99  GNSSRaw gnss_raw_read() override;
100  bool gnss_has_new_data() override;
101 
102 
103 // RC
104  void rc_init(rc_type_t rc_type) override;
105  bool rc_lost() override;
106  float rc_read(uint8_t channel) override;
107 
108 // PWM
109  void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override;
110  void pwm_disable() override;
111  void pwm_write(uint8_t channel, float value) override;
112 
113 // non-volatile memory
114  void memory_init() override;
115  bool memory_read(void *dest, size_t len) override;
116  bool memory_write(const void *src, size_t len) override;
117 
118 // LEDs
119  void led0_on() override;
120  void led0_off() override;
121  void led0_toggle() override;
122 
123  void led1_on() override;
124  void led1_off() override;
125  void led1_toggle() override;
126 
127 //Backup memory
128  bool has_backup_data() override;
129  BackupData get_backup_data() override;
130 
131 
132  void set_imu(float *acc, float *gyro, uint64_t time_us);
133  void set_rc(uint16_t *values);
134  void set_time(uint64_t time_us);
135  void set_pwm_lost(bool lost);
136 
137 };
138 
139 } // namespace rosflight_firmware
140 
141 #endif // ROSLFIGHT_FIRMWARE_TEST_BOARD_H
uint32_t clock_millis() override
Definition: test_board.cpp:75
void pwm_write(uint8_t channel, float value) override
Definition: test_board.cpp:191
static volatile int16_t gyro[3]
Definition: drv_mpu6050.c:277
bool gnss_present() override
Definition: test_board.h:93
void board_reset(bool bootloader) override
Definition: test_board.cpp:72
void serial_init(uint32_t baud_rate, uint32_t dev) override
Definition: test_board.cpp:86
float pressure
Definition: ms4525.c:41
void mag_read(float mag[3]) override
Definition: test_board.cpp:135
float temperature
Definition: ms4525.c:41
void set_imu(float *acc, float *gyro, uint64_t time_us)
Definition: test_board.cpp:58
bool diff_pressure_present() override
Definition: test_board.cpp:144
uint16_t serial_bytes_available() override
Definition: test_board.cpp:88
void sensors_init() override
Definition: test_board.cpp:99
uint64_t clock_micros() override
Definition: test_board.cpp:79
void rc_init(rc_type_t rc_type) override
Definition: test_board.cpp:182
void set_rc(uint16_t *values)
Definition: test_board.cpp:40
bool has_backup_data() override
Definition: test_board.cpp:216
float rc_read(uint8_t channel) override
Definition: test_board.cpp:187
static volatile int16_t accel[3]
Definition: drv_mpu6050.c:276
GNSSRaw gnss_raw_read() override
Definition: test_board.cpp:168
uint8_t serial_read() override
Definition: test_board.cpp:92
void baro_read(float *pressure, float *temperature) override
Definition: test_board.cpp:142
void serial_flush() override
Definition: test_board.cpp:96
void gnss_update() override
Definition: test_board.h:97
bool gnss_has_new_data() override
Definition: test_board.cpp:174
void diff_pressure_read(float *diff_pressure, float *temperature) override
Definition: test_board.cpp:149
void set_time(uint64_t time_us)
Definition: test_board.cpp:48
BackupData get_backup_data() override
Definition: test_board.cpp:220
bool memory_read(void *dest, size_t len) override
Definition: test_board.cpp:197
void diff_pressure_update() override
Definition: test_board.cpp:148
bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t *time) override
Definition: test_board.cpp:116
void clock_delay(uint32_t milliseconds) override
Definition: test_board.cpp:83
void imu_not_responding_error() override
Definition: test_board.cpp:128
GNSSData gnss_read() override
Definition: test_board.cpp:162
void set_pwm_lost(bool lost)
Definition: test_board.cpp:53
void serial_write(const uint8_t *src, size_t len) override
Definition: test_board.cpp:87
bool memory_write(const void *src, size_t len) override
Definition: test_board.cpp:201
void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override
Definition: test_board.cpp:192


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