Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp
9584 views
1
#include <AP_HAL/AP_HAL.h>
2
3
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
4
5
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
6
void setup() { }
7
8
void loop()
9
{
10
// the library simply panics if a JEDEC device can't be found. We
11
// can't really recover from that.
12
hal.console->printf("No JEDEC on linux\n");
13
hal.scheduler->delay(1000);
14
}
15
16
#else
17
18
#include <GCS_MAVLink/GCS_Dummy.h>
19
#include <AP_SerialManager/AP_SerialManager.h>
20
#include <AP_BoardConfig/AP_BoardConfig.h>
21
#include <AP_FlashIface/AP_FlashIface.h>
22
#include <stdio.h>
23
24
AP_FlashIface_JEDEC jedec_dev;
25
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
26
27
void setup();
28
void loop();
29
30
GCS_Dummy _gcs;
31
32
33
#ifdef HAL_BOOTLOADER_BUILD
34
#define DELAY_MILLIS(x) do { chThdSleepMilliseconds(x); } while(0)
35
#define DELAY_MICROS(x) do { chThdSleepMicroseconds(x); } while(0)
36
#else
37
#define DELAY_MILLIS(x) do { hal.scheduler->delay(x); } while(0)
38
#define DELAY_MICROS(x) do { hal.scheduler->delay_microseconds(x); } while(0)
39
#endif
40
41
static AP_SerialManager serial_manager;
42
static AP_BoardConfig board_config;
43
44
static UNUSED_FUNCTION void test_page_program()
45
{
46
uint8_t *data = new uint8_t[jedec_dev.get_page_size()];
47
if (data == nullptr) {
48
hal.console->printf("Failed to allocate data for program");
49
}
50
uint8_t *rdata = new uint8_t[jedec_dev.get_page_size()];
51
if (rdata == nullptr) {
52
hal.console->printf("Failed to allocate data for read");
53
}
54
55
// fill program data with its own address
56
for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) {
57
data[i] = i;
58
}
59
hal.console->printf("Writing Page #1\n");
60
uint32_t delay_us, timeout_us;
61
uint64_t start_time_us = AP_HAL::micros64();
62
if (!jedec_dev.start_program_page(0, data, delay_us, timeout_us)) {
63
hal.console->printf("Page write command failed\n");
64
return;
65
}
66
while (true) {
67
DELAY_MICROS(delay_us);
68
if (AP_HAL::micros64() > (start_time_us+delay_us)) {
69
if (!jedec_dev.is_device_busy()) {
70
hal.console->printf("Page Program Successful, elapsed %ld us\n", (unsigned long)(AP_HAL::micros64() - start_time_us));
71
break;
72
} else {
73
hal.console->printf("Typical page program time reached, Still Busy?!\n");
74
}
75
}
76
if (AP_HAL::micros64() > (start_time_us+timeout_us)) {
77
hal.console->printf("Page Program Timed out, elapsed %lld us\n", (unsigned long long)(AP_HAL::micros64() - start_time_us));
78
return;
79
}
80
}
81
if (!jedec_dev.read(0, rdata, jedec_dev.get_page_size())) {
82
hal.console->printf("Failed to read Flash page\n");
83
} else {
84
if (memcmp(data, rdata, jedec_dev.get_page_size()) != 0) {
85
hal.console->printf("Program Data Mismatch!\n");
86
} else {
87
hal.console->printf("Program Data Verified Good!\n");
88
}
89
}
90
91
// Now test XIP mode here as well
92
uint8_t *chip_data = nullptr;
93
if (!jedec_dev.start_xip_mode((void**)&chip_data)) {
94
hal.console->printf("Failed to setup XIP mode\n");
95
}
96
if (chip_data == nullptr) {
97
hal.console->printf("Invalid address!\n");
98
}
99
// Here comes the future!
100
if (memcmp(data, chip_data, jedec_dev.get_page_size()) != 0) {
101
hal.console->printf("Program Data Mismatch in XIP mode!\n");
102
} else {
103
hal.console->printf("Program Data Verified Good in XIP mode!\n");
104
}
105
jedec_dev.stop_xip_mode();
106
}
107
108
static UNUSED_FUNCTION void test_sector_erase()
109
{
110
uint32_t delay_ms, timeout_ms;
111
if (!jedec_dev.start_sector_erase(0, delay_ms, timeout_ms)) { // erase first sector
112
hal.console->printf("Sector erase command failed\n");
113
return;
114
}
115
uint32_t erase_start = AP_HAL::millis();
116
uint32_t next_check_ms = 0;
117
hal.console->printf("Erasing Sector #1 ");
118
while (true) {
119
if (AP_HAL::millis() > next_check_ms) {
120
hal.console->printf("\n");
121
if (!jedec_dev.is_device_busy()) {
122
if (next_check_ms == 0) {
123
hal.console->printf("Sector Erase happened too fast\n");
124
return;
125
}
126
hal.console->printf("Sector Erase Successful, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));
127
break;
128
} else {
129
hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));
130
}
131
if ((AP_HAL::millis() - erase_start) > timeout_ms) {
132
hal.console->printf("Sector Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));
133
return;
134
}
135
next_check_ms = erase_start+delay_ms;
136
}
137
DELAY_MILLIS((delay_ms/100) + 10);
138
hal.console->printf("*");
139
}
140
if (!jedec_dev.verify_sector_erase(0)) {
141
hal.console->printf("Erase Verification Failed!\n");
142
} else {
143
hal.console->printf("Erase Verification Successful!\n");
144
}
145
}
146
147
static UNUSED_FUNCTION void test_mass_erase()
148
{
149
uint32_t delay_ms, timeout_ms;
150
if (!jedec_dev.start_mass_erase(delay_ms, timeout_ms)) {
151
hal.console->printf("Mass erase command failed\n");
152
return;
153
}
154
uint32_t erase_start = AP_HAL::millis();
155
uint32_t next_check_ms = 0;
156
hal.console->printf("Mass Erasing ");
157
while (true) {
158
if (AP_HAL::millis() > next_check_ms) {
159
hal.console->printf("\n");
160
if (!jedec_dev.is_device_busy()) {
161
if (next_check_ms == 0) {
162
hal.console->printf("Sector Erase happened too fast\n");
163
return;
164
}
165
hal.console->printf("Mass Erase Successful, elapsed %ld ms\n",(unsigned long)(AP_HAL::millis() - erase_start));
166
return;
167
} else {
168
hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));
169
}
170
if ((AP_HAL::millis() - erase_start) > timeout_ms) {
171
hal.console->printf("Mass Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));
172
return;
173
}
174
next_check_ms = erase_start+delay_ms;
175
}
176
DELAY_MILLIS(delay_ms/100);
177
hal.console->printf("*");
178
}
179
}
180
181
void setup()
182
{
183
board_config.init();
184
serial_manager.init();
185
}
186
187
void loop()
188
{
189
// Start on user input
190
hal.console->printf("\n\n******************Starting Test********************\n");
191
jedec_dev.init();
192
test_sector_erase();
193
test_page_program();
194
// test_mass_erase();
195
hal.scheduler->delay(1000);
196
}
197
198
#endif
199
200
AP_HAL_MAIN();
201
202
203