src
main_csvlogger.c
Go to the documentation of this file.
1
//==============================================================================
2
//
3
// main_csvlogger.c - Epson IMU sensor test application
4
// - This program initializes the Epson IMU and
5
// sends sensor output to CSV file
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
#include <stdint.h>
18
#include <stdio.h>
19
#include <string.h>
20
#include <termios.h>
21
#include <
time.h
>
22
23
#include "
hcl.h
"
24
#include "
hcl_gpio.h
"
25
#include "
hcl_uart.h
"
26
#include "
main_helper.h
"
27
#include "
sensor_epsonCommon.h
"
28
29
int
fd_serial
;
30
31
// Modify below as needed for hardware
32
const
char
*
IMUSERIAL
=
"/dev/ttyUSB0"
;
33
34
// Specify the number of samples to readout before exiting the program
35
const
unsigned
int
NUM_SAMPLES
= 100;
36
37
int
main
(
int
argc,
char
*argv[]) {
38
unsigned
int
sample = 0;
39
char
prod_id[9];
// Device Product ID
40
char
ser_id[9];
// Device Serial ID
41
42
// Specify IMU options
43
struct
EpsonOptions
options = {
44
.
ext_sel
= 1,
// 0 = Sample Counter 1=Reset Counter 2=External Trigger
45
.ext_pol = 0,
46
.drdy_on = 0,
47
.drdy_pol = 0,
48
.dout_rate =
CMD_RATE125
,
49
.filter_sel =
CMD_FLTAP32
,
50
.flag_out = 1,
51
.temp_out = 1,
52
.gyro_out = 1,
53
.accel_out = 1,
54
.gyro_delta_out = 0,
55
.accel_delta_out = 0,
56
.qtn_out = 0,
// Only valid for G365, G330, G366 otherwise ignored
57
.atti_out = 0,
// Only valid for G365, G330, G366 otherwise ignored
58
.gpio_out = 0,
59
.count_out = 1,
60
.checksum_out = 1,
61
62
// Set 0=16bit 1=32bit sensor output
63
.temp_bit = 0,
64
.gyro_bit = 0,
65
.accel_bit = 0,
66
.gyro_delta_bit = 0,
67
.accel_delta_bit = 0,
68
.qtn_bit = 0,
69
.atti_bit = 0,
70
71
// Set 0=normal 1=reverse polarity
72
.invert_xgyro = 0,
73
.invert_ygyro = 0,
74
.invert_zgyro = 0,
75
.invert_xaccel = 0,
76
.invert_yaccel = 0,
77
.invert_zaccel = 0,
78
79
.dlt_ovf_en = 0,
80
.dlt_range_ctrl = 8,
81
82
// NOTE: // Only valid for G330, G365, G366 otherwise ignored
83
.atti_mode = 1,
// 0=Inclination mode 1=Euler mode
84
.atti_conv = 0,
// Attitude Conversion Mode
85
.atti_profile = 0
// Attitude Motion Profile 0=modeA 1=modeB 2=modeC
86
};
87
88
// Stores the post-processed sensor data
89
struct
EpsonData
epson_data;
90
91
// 1) Initialize the Seiko Epson HCL layer
92
printf(
"\r\nInitializing HCL layer..."
);
93
if
(!
seInit
()) {
94
printf(
95
"\r\nError: could not initialize the Seiko Epson HCL layer. "
96
"Exiting...\r\n"
);
97
return
-1;
98
}
99
printf(
"...done.\r\n"
);
100
101
// 2) Initialize the GPIO interfaces, For GPIO control of pins SPI CS, RESET,
102
// DRDY
103
printf(
"\r\nInitializing GPIO interface..."
);
104
if
(!
gpioInit
()) {
105
printf(
"\r\nError: could not initialize the GPIO layer. Exiting...\r\n"
);
106
seRelease
();
107
return
-1;
108
}
109
printf(
"...done.\r\n"
);
110
111
// 3) Initialize UART Interface
112
// The baudrate value should be set the the same setting as currently
113
// flashed value in the IMU UART_CTRL BAUD_RATE register
114
printf(
"\r\nInitializing UART interface..."
);
115
fd_serial
=
uartInit
(
IMUSERIAL
,
BAUD_460800
);
116
if
(
fd_serial
== -1) {
117
printf(
"\r\nError: could not initialize UART interface. Exiting...\r\n"
);
118
gpioRelease
();
119
seRelease
();
120
return
-1;
121
}
122
printf(
"...done.\r\n"
);
123
124
// 4) Power on sequence - force sensor to config mode, HW reset sensor
125
// Check for errors
126
printf(
"\r\nChecking sensor NOT_READY status..."
);
127
if
(!
sensorPowerOn
()) {
128
printf(
"\r\nError: failed to power on Sensor. Exiting...\r\n"
);
129
uartRelease
(
fd_serial
);
130
gpioRelease
();
131
seRelease
();
132
return
-1;
133
}
134
printf(
"...done.\r\n"
);
135
136
// Print out which model executable was compiled and identify model
137
printf(
"\r\nCompiled for:\t"
BUILD_FOR);
138
printf(
"\r\nReading device info..."
);
139
if
(strcmp(BUILD_FOR,
getProductId
(prod_id)) != 0) {
140
printf(
"\r\n*** Build *mismatch* with detected device ***"
);
141
printf(
142
"\r\n*** Ensure you specify a compatible 'MODEL=' variable when "
143
"running make when rebuilding the driver ***\r\n"
);
144
}
145
printf(
"\r\nPRODUCT ID:\t%s"
, prod_id);
146
printf(
"\r\nSERIAL ID:\t%s"
,
getSerialId
(ser_id));
147
148
// Initialize sensor with desired settings
149
printf(
"\r\nInitializing Sensor..."
);
150
if
(!
sensorInitOptions
(options)) {
151
printf(
"\r\nError: could not initialize Epson Sensor. Exiting...\r\n"
);
152
uartRelease
(
fd_serial
);
153
gpioRelease
();
154
seRelease
();
155
return
-1;
156
}
157
printf(
"...Epson IMU initialized.\r\n"
);
158
159
// Initialize text files for data logs
160
const
time_t date =
161
time(NULL);
// Functions for obtaining and printing time and date
162
struct
tm tm = *localtime(&date);
163
char
EpsonlogName[128];
164
165
// Create Epson IMU Data Log
166
sprintf(EpsonlogName,
"EpsonLog_%4d-%02d-%02d_T%02d-%02d-%02d.csv"
,
167
tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday, tm.tm_hour, tm.tm_min,
168
tm.tm_sec);
169
FILE *EpsonLog = fopen(EpsonlogName,
"w"
);
170
fprintf(EpsonLog,
"#PRODUCT_ID: %s"
, prod_id);
171
fprintf(EpsonLog,
"\r\n#SERIAL_ID: %s"
, ser_id);
172
fprintf(EpsonLog,
"\r\n#Date: %s"
, ctime(&date));
173
printf(
"\r\n...Epson IMU Logging.\r\n"
);
174
sensorStart
();
175
printHeaderRow
(EpsonLog, options);
176
while
(1) {
177
// For SPI interface, check if DRDY pin asserted
178
// For UART interface, check if UART recv buffer contains a sensor sample
179
// packet
180
if
(
sensorDataReadyOptions
(options)) {
181
if
(
sensorDataReadBurstNOptions
(options, &epson_data) ==
OK
) {
182
printSensorRow
(EpsonLog, options, &epson_data, sample);
183
sample++;
184
}
185
}
186
if
(sample > (
NUM_SAMPLES
- 1))
break
;
187
}
188
189
const
time_t end =
190
time(NULL);
// Functions for obtaining and printing time and data
191
fprintf(EpsonLog,
"\r\n#End: "
);
192
fprintf(EpsonLog,
"%s"
, ctime(&end));
193
194
sensorStop
();
195
seDelayMS
(1000);
196
uartRelease
(
fd_serial
);
197
gpioRelease
();
198
seRelease
();
199
fclose(EpsonLog);
200
printf(
"\r\n"
);
201
return
0;
202
}
main
int main(int argc, char *argv[])
Definition:
main_csvlogger.c:37
sensor_epsonCommon.h
getSerialId
char * getSerialId(char *pcharArr)
Definition:
sensor_epsonCommon.c:391
EpsonOptions::ext_sel
int ext_sel
Definition:
sensor_epsonCommon.h:72
seDelayMS
void seDelayMS(uint32_t millis)
Definition:
hcl_linux.c:46
main_helper.h
time.h
CMD_RATE125
#define CMD_RATE125
Definition:
sensor_epsonG320.h:157
hcl_gpio.h
uartRelease
int uartRelease(ComPortHandle fd_serial)
Definition:
hcl_uart.c:83
NUM_SAMPLES
const unsigned int NUM_SAMPLES
Definition:
main_csvlogger.c:35
sensorDataReadBurstNOptions
int sensorDataReadBurstNOptions(struct EpsonOptions, struct EpsonData *)
Definition:
sensor_epsonUart.c:528
fd_serial
int fd_serial
Definition:
main_csvlogger.c:29
EpsonOptions
Definition:
sensor_epsonCommon.h:70
gpioInit
int gpioInit(void)
Definition:
hcl_gpio.c:33
hcl.h
printSensorRow
void printSensorRow(FILE *fp, struct EpsonOptions options, struct EpsonData *epson_data, int sample_count)
Definition:
main_helper.c:88
seRelease
int seRelease(void)
Definition:
hcl_linux.c:38
BAUD_460800
#define BAUD_460800
Definition:
hcl_uart.h:24
EpsonData
Definition:
sensor_epsonCommon.h:126
printHeaderRow
void printHeaderRow(FILE *fp, struct EpsonOptions options)
Definition:
main_helper.c:30
uartInit
int uartInit(const char *comPortPath, int baudrate)
Definition:
hcl_uart.c:52
sensorDataReadyOptions
int sensorDataReadyOptions(struct EpsonOptions)
Definition:
sensor_epsonUart.c:62
gpioRelease
int gpioRelease(void)
Definition:
hcl_gpio.c:41
sensorStop
void sensorStop(void)
Definition:
sensor_epsonCommon.c:113
CMD_FLTAP32
#define CMD_FLTAP32
Definition:
sensor_epsonG320.h:176
sensorPowerOn
int sensorPowerOn(void)
Definition:
sensor_epsonCommon.c:63
sensorStart
void sensorStart(void)
Definition:
sensor_epsonCommon.c:100
IMUSERIAL
const char * IMUSERIAL
Definition:
main_csvlogger.c:32
getProductId
char * getProductId(char *pcharArr)
Definition:
sensor_epsonCommon.c:365
sensorInitOptions
int sensorInitOptions(struct EpsonOptions)
Definition:
sensor_epsonG320.c:28
seInit
int seInit(void)
Definition:
hcl_linux.c:30
OK
#define OK
Definition:
hcl.h:29
hcl_uart.h
ess_imu_ros1_uart_driver
Author(s):
autogenerated on Sun Dec 3 2023 03:11:32