Main Page
Classes
Class List
Class Members
All
a
c
d
e
f
g
h
i
m
n
o
p
q
r
s
t
Functions
Variables
a
c
d
e
f
g
h
i
m
n
o
p
q
r
t
Files
File List
File Members
All
a
b
c
d
e
f
g
h
i
m
n
o
p
r
s
u
v
w
Functions
c
d
g
i
m
n
o
p
r
s
u
w
Variables
Enumerations
Enumerator
Macros
a
b
c
d
e
f
m
n
o
r
s
v
w
src
main_screen.c
Go to the documentation of this file.
1
//==============================================================================
2
//
3
// main_screen.c - Epson IMU sensor test application
4
// - This program initializes the Epson IMU and
5
// sends sensor output to console
6
//
7
//
8
// THE SOFTWARE IS RELEASED INTO THE PUBLIC DOMAIN.
9
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
10
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
11
// NONINFRINGEMENT, SECURITY, SATISFACTORY QUALITY, AND FITNESS FOR A
12
// PARTICULAR PURPOSE. IN NO EVENT SHALL EPSON BE LIABLE FOR ANY LOSS, DAMAGE
13
// OR CLAIM, ARISING FROM OR IN CONNECTION WITH THE SOFTWARE OR THE USE OF THE
14
// SOFTWARE.
15
//
16
//==============================================================================
17
18
#include <stdint.h>
19
#include <stdio.h>
20
#include <string.h>
21
#include <
time.h
>
22
23
#ifdef SPI
24
#else
25
#include <termios.h>
26
#endif // SPI
27
28
#include "
hcl.h
"
29
#include "
hcl_gpio.h
"
30
31
#ifdef SPI
32
#include "
hcl_spi.h
"
33
#else
34
#include "
hcl_uart.h
"
35
#endif // SPI
36
37
#include "
main_helper.h
"
38
#include "
sensor_epsonCommon.h
"
39
40
#ifdef SPI
41
#else
42
43
// Modify below as needed for hardware
44
const
char
*
IMUSERIAL
=
"/dev/ttyUSB0"
;
45
#endif // SPI
46
47
// Specify the number of samples to readout before exiting the program
48
const
unsigned
int
NUM_SAMPLES
= 1000;
49
50
int
main
(
int
argc,
char
*argv[]) {
51
char
prod_id[9];
// Device Product ID
52
char
ser_id[9];
// Device Serial ID
53
struct
EpsonProperties
epson_sensor =
epson_sensors
[
G_UNKNOWN
];
54
55
// Specify IMU options
56
struct
EpsonOptions
epson_options = {
57
.
ext_sel
= 1,
// 0 = Sample Counter 1=Reset Counter 2=External Trigger
58
.ext_pol = 0,
59
#ifdef SPI
60
.drdy_on = 1,
61
#endif // SPI
62
.drdy_pol = 1,
63
.dout_rate =
CMD_RATE125
,
64
.filter_sel =
CMD_FLTAP32
,
65
.flag_out = 1,
66
.temp_out = 1,
67
.gyro_out = 1,
68
.accel_out = 1,
69
.gyro_delta_out = 0,
70
.accel_delta_out = 0,
71
.qtn_out = 0,
// Only valid for devices that support attitude output
72
.atti_out = 0,
// Only valid for devices that support attitude output
73
.count_out = 1,
74
.checksum_out = 1,
75
76
// Set 0=16bit 1=32bit sensor output.
77
// These only have effect if above related "_out = 1"
78
.temp_bit = 1,
79
.gyro_bit = 1,
80
.accel_bit = 1,
81
.gyro_delta_bit = 1,
82
.accel_delta_bit = 1,
83
.qtn_bit = 1,
84
.atti_bit = 1,
85
86
.dlta_range_ctrl = 8,
87
.dltv_range_ctrl = 8,
88
89
// NOTE: The following are only valid when attitude output is enabled
90
.atti_mode = 1,
// 0=Inclination mode 1=Euler mode
91
.atti_conv = 0,
// Attitude Conversion Mode, must be 0 when quaternion
92
// output is enabled
93
.atti_profile = 0
// Attitude Motion Profile 0=modeA 1=modeB 2=modeC
94
};
95
96
// Stores the post-processed sensor data
97
struct
EpsonData
epson_data;
98
99
// 1) Initialize the Seiko Epson HCL layer
100
printf(
"\r\nInitializing HCL layer..."
);
101
if
(!
seInit
()) {
102
printf(
103
"\r\nError: could not initialize the Seiko Epson HCL layer. "
104
"Exiting...\r\n"
);
105
return
-1;
106
}
107
printf(
"...done.\r\n"
);
108
109
// 2) Initialize the GPIO interfaces, For GPIO control of pins SPI CS, RESET,
110
// DRDY
111
printf(
"\r\nInitializing GPIO interface..."
);
112
if
(!
gpioInit
()) {
113
printf(
"\r\nError: could not initialize the GPIO layer. Exiting...\r\n"
);
114
seRelease
();
115
return
-1;
116
}
117
printf(
"...done.\r\n"
);
118
119
#ifdef SPI
120
// 3) Initialize SPI Interface
121
printf(
"\r\nInitializing SPI interface..."
);
122
// The max SPI clock rate is 1MHz for burst reads in Epson IMUs
123
if
(!
spiInit
(
SPI_MODE3
, 1000000)) {
124
printf(
"\r\nError: could not initialize SPI interface. Exiting...\r\n"
);
125
gpioRelease
();
126
seRelease
();
127
return
-1;
128
}
129
sensorDummyWrite
();
130
#else
131
// 3) Initialize UART Interface
132
// The baudrate value should be set the the same setting as currently
133
// flashed value in the IMU UART_CTRL BAUD_RATE register
134
printf(
"\r\nInitializing UART interface..."
);
135
if
(!
uartInit
(
IMUSERIAL
,
BAUD_460800
)) {
136
printf(
"\r\nError: could not initialize UART interface. Exiting...\r\n"
);
137
gpioRelease
();
138
seRelease
();
139
return
-1;
140
}
141
#endif // SPI
142
143
printf(
"...done.\r\n"
);
144
145
// 4) Power on sequence - force sensor to config mode, read ID and
146
// check for errors
147
148
printf(
"\r\nSensor starting up..."
);
149
if
(!
sensorPowerOn
()) {
150
printf(
"\r\nError: failed to power on sensor. Exiting...\r\n"
);
151
152
#ifdef SPI
153
spiRelease
();
154
#else
155
uartRelease
();
156
#endif
157
158
gpioRelease
();
159
seRelease
();
160
return
-1;
161
}
162
printf(
"...done.\r\n"
);
163
164
// Auto-Detect Epson Sensor Model Properties
165
printf(
"\r\nDetecting sensor model..."
);
166
if
(!
sensorGetDeviceModel
(&epson_sensor, prod_id, ser_id)) {
167
printf(
"\r\nError: could not detect Epson Sensor. Exiting...\r\n"
);
168
169
#ifdef SPI
170
spiRelease
();
171
#else
172
uartRelease
();
173
#endif
174
175
gpioRelease
();
176
seRelease
();
177
return
-1;
178
}
179
180
// Initialize sensor with desired settings
181
printf(
"\r\nInitializing sensor..."
);
182
if
(!
sensorInitOptions
(&epson_sensor, &epson_options)) {
183
printf(
"\r\nError: could not initialize Epson Sensor. Exiting...\r\n"
);
184
185
#ifdef SPI
186
spiRelease
();
187
#else
188
uartRelease
();
189
#endif
190
191
gpioRelease
();
192
seRelease
();
193
return
-1;
194
}
195
printf(
"...Epson IMU initialized.\r\n"
);
196
197
// Initialize text files for data logs
198
const
time_t date =
199
time(NULL);
// Functions for obtaining and printing time and date
200
201
printf(
"Date: %s"
, ctime(&date));
202
printf(
"...Epson IMU Logging.\r\n"
);
203
sensorStart
();
204
printHeaderRow
(stdout, &epson_options);
205
206
unsigned
int
sample = 0;
207
while
(sample < (
NUM_SAMPLES
- 1)) {
208
if
(
sensorDataReadBurstNOptions
(&epson_sensor, &epson_options,
209
&epson_data) ==
OK
) {
210
printSensorRow
(stdout, &epson_options, &epson_data, sample);
211
sample++;
212
}
213
}
214
215
const
time_t end =
216
time(NULL);
// Functions for obtaining and printing time and data
217
218
printf(
"\r\nEnd: "
);
219
printf(
"%s"
, ctime(&end));
220
221
sensorStop
();
222
seDelayMS
(1000);
223
224
#ifdef SPI
225
spiRelease
();
226
#else
227
uartRelease
();
228
#endif
229
230
gpioRelease
();
231
seRelease
();
232
printf(
"\r\n"
);
233
return
0;
234
}
spiRelease
int spiRelease(void)
Definition:
hcl_spi_rpi.c:67
sensorInitOptions
int sensorInitOptions(const struct EpsonProperties *esensor, struct EpsonOptions *options)
Definition:
sensor_epsonCommon.c:835
EpsonProperties
Definition:
sensor_epsonCommon.h:314
sensor_epsonCommon.h
EpsonOptions::ext_sel
int ext_sel
Definition:
sensor_epsonCommon.h:342
sensorDataReadBurstNOptions
int sensorDataReadBurstNOptions(const struct EpsonProperties *, const struct EpsonOptions *, struct EpsonData *)
Definition:
sensor_epsonSpi.c:451
seDelayMS
void seDelayMS(uint32_t millis)
Definition:
hcl_linux.c:47
main_helper.h
time.h
hcl_gpio.h
NUM_SAMPLES
const unsigned int NUM_SAMPLES
Definition:
main_screen.c:48
EpsonOptions
Definition:
sensor_epsonCommon.h:340
gpioInit
int gpioInit(void)
Definition:
hcl_gpio.c:32
hcl.h
IMUSERIAL
const char * IMUSERIAL
Definition:
main_screen.c:44
printSensorRow
void printSensorRow(FILE *fp, const struct EpsonOptions *options, const struct EpsonData *epson_data, int sample_count)
Definition:
main_helper.c:88
CMD_FLTAP32
#define CMD_FLTAP32
Definition:
sensor_epsonCommon.h:253
seRelease
int seRelease(void)
Definition:
hcl_linux.c:39
BAUD_460800
#define BAUD_460800
Definition:
hcl_uart.h:26
EpsonData
Definition:
sensor_epsonCommon.h:399
main
int main(int argc, char *argv[])
Definition:
main_screen.c:50
uartInit
int uartInit(const char *comPortPath, int baudrate)
Definition:
hcl_uart.c:50
printHeaderRow
void printHeaderRow(FILE *fp, const struct EpsonOptions *options)
Definition:
main_helper.c:30
gpioRelease
int gpioRelease(void)
Definition:
hcl_gpio.c:40
sensorStop
void sensorStop(void)
Definition:
sensor_epsonCommon.c:504
uartRelease
int uartRelease(void)
Definition:
hcl_uart.c:98
hcl_spi.h
sensorPowerOn
int sensorPowerOn(void)
Definition:
sensor_epsonCommon.c:445
SPI_MODE3
@ SPI_MODE3
Definition:
hcl_spi.h:26
sensorStart
void sensorStart(void)
Definition:
sensor_epsonCommon.c:490
G_UNKNOWN
@ G_UNKNOWN
Definition:
sensor_epsonCommon.h:299
CMD_RATE125
#define CMD_RATE125
Definition:
sensor_epsonCommon.h:234
spiInit
int spiInit(uint8_t mode, uint32_t khzspeed)
Definition:
hcl_spi_rpi.c:45
epson_sensors
struct EpsonProperties epson_sensors[]
Definition:
sensor_epsonCommon.c:28
sensorDummyWrite
void sensorDummyWrite(void)
Definition:
sensor_epsonCommon.c:766
seInit
int seInit(void)
Definition:
hcl_linux.c:31
OK
#define OK
Definition:
hcl.h:26
sensorGetDeviceModel
int sensorGetDeviceModel(struct EpsonProperties *esensor, char *prod_id, char *serial_id)
Definition:
sensor_epsonCommon.c:1192
hcl_uart.h
ess_imu_driver
Author(s):
autogenerated on Wed Dec 11 2024 03:06:30