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 
18 #include <stdint.h>
19 #include <stdio.h>
20 #include <string.h>
21 #include <time.h>
22 
23 #ifndef SPI
24 #include <termios.h>
25 #endif // !SPI
26 
27 #include "hcl.h"
28 #include "hcl_gpio.h"
29 
30 #ifdef SPI
31 #include "hcl_spi.h"
32 #else
33 #include "hcl_uart.h"
34 #endif // SPI
35 
36 #include "main_helper.h"
37 #include "sensor_epsonCommon.h"
38 
39 #ifndef SPI
40 // Modify below as needed for hardware
41 const char *IMUSERIAL = "/dev/ttyUSB0";
42 #endif // !SPI
43 
44 // Specify the number of samples to readout before exiting the program
45 const unsigned int NUM_SAMPLES = 1000;
46 
47 int main(int argc, char *argv[]) {
48  char prod_id[9]; // Device Product ID
49  char ser_id[9]; // Device Serial ID
50  struct EpsonProperties epson_sensor = epson_sensors[G_UNKNOWN];
51 
52  // Specify IMU options
53  struct EpsonOptions epson_options = {
54  .ext_sel = 1, // 0 = Sample Counter 1=Reset Counter 2=External Trigger
55  .ext_pol = 0,
56 #ifdef SPI
57  .drdy_on = 1,
58 #endif // SPI
59  .drdy_pol = 1,
60  .dout_rate = CMD_RATE125,
61  .filter_sel = CMD_FLTAP32,
62  .flag_out = 1,
63  .temp_out = 1,
64  .gyro_out = 1,
65  .accel_out = 1,
66  .gyro_delta_out = 0,
67  .accel_delta_out = 0,
68  .qtn_out = 0, // Only valid for devices that support attitude output
69  .atti_out = 0, // Only valid for devices that support attitude output
70  .count_out = 1,
71  .checksum_out = 1,
72 
73  // Set 0=16bit 1=32bit sensor output.
74  // These only have effect if above related "_out = 1"
75  .temp_bit = 1,
76  .gyro_bit = 1,
77  .accel_bit = 1,
78  .gyro_delta_bit = 0,
79  .accel_delta_bit = 0,
80  .qtn_bit = 0,
81  .atti_bit = 0,
82 
83  .dlta_range_ctrl = 8,
84  .dltv_range_ctrl = 8,
85 
86  // NOTE: The following are only valid when attitude output is enabled
87  .atti_mode = 1, // 0=Inclination mode 1=Euler mode
88  .atti_conv = 0, // Attitude Conversion Mode, must be 0 when quaternion
89  // output is enabled
90  .atti_profile = 0 // Attitude Motion Profile 0=modeA 1=modeB 2=modeC
91  };
92 
93  // Stores the post-processed sensor data
94  struct EpsonData epson_data;
95 
96  // 1) Initialize the Seiko Epson HCL layer
97  printf("\r\nInitializing HCL layer...");
98  if (!seInit()) {
99  printf(
100  "\r\nError: could not initialize the Seiko Epson HCL layer. "
101  "Exiting...\r\n");
102  return -1;
103  }
104  printf("...done.\r\n");
105 
106  // 2) Initialize the GPIO interfaces, For GPIO control of pins SPI CS, RESET,
107  // DRDY
108  printf("\r\nInitializing GPIO interface...");
109  if (!gpioInit()) {
110  printf("\r\nError: could not initialize the GPIO layer. Exiting...\r\n");
111  seRelease();
112  return -1;
113  }
114  printf("...done.\r\n");
115 
116 #ifdef SPI
117  // 3) Initialize SPI Interface
118  printf("\r\nInitializing SPI interface...");
119  // The max SPI clock rate is 1MHz for burst reads in Epson IMUs
120  if (!spiInit(SPI_MODE3, 1000000)) {
121  printf("\r\nError: could not initialize SPI interface. Exiting...\r\n");
122  gpioRelease();
123  seRelease();
124  return -1;
125  }
127 #else
128  // 3) Initialize UART Interface
129  // The baudrate value should be set the the same setting as currently
130  // flashed value in the IMU UART_CTRL BAUD_RATE register
131  printf("\r\nInitializing UART interface...");
132  if (!uartInit(IMUSERIAL, BAUD_460800)) {
133  printf("\r\nError: could not initialize UART interface. Exiting...\r\n");
134  gpioRelease();
135  seRelease();
136  return -1;
137  }
138 #endif // SPI
139 
140  printf("...done.\r\n");
141 
142  // 4) Power on sequence - force sensor to config mode, read ID and
143  // check for errors
144 
145  printf("\r\nSensor starting up...");
146  if (!sensorPowerOn()) {
147  printf("\r\nError: failed to power on Sensor. Exiting...\r\n");
148 
149 #ifdef SPI
150  spiRelease();
151 #else
152  uartRelease();
153 #endif
154 
155  gpioRelease();
156  seRelease();
157  return -1;
158  }
159  printf("...done.\r\n");
160 
161  // Auto-Detect Epson Sensor Model Properties
162  printf("\r\nDetecting sensor model...");
163  if (!sensorGetDeviceModel(&epson_sensor, prod_id, ser_id)) {
164  printf("\r\nError: could not detect Epson Sensor. Exiting...\r\n");
165 
166 #ifdef SPI
167  spiRelease();
168 #else
169  uartRelease();
170 #endif
171 
172  gpioRelease();
173  seRelease();
174  return -1;
175  }
176 
177  // Initialize sensor with desired settings
178  printf("\r\nInitializing Sensor...");
179  if (!sensorInitOptions(&epson_sensor, &epson_options)) {
180  printf("\r\nError: could not initialize Epson Sensor. Exiting...\r\n");
181 
182 #ifdef SPI
183  spiRelease();
184 #else
185  uartRelease();
186 #endif
187 
188  gpioRelease();
189  seRelease();
190  return -1;
191  }
192  printf("...Epson IMU initialized.\r\n");
193 
194  // Initialize text files for data logs
195  const time_t date =
196  time(NULL); // Functions for obtaining and printing time and date
197  struct tm tm = *localtime(&date);
198  char EpsonlogName[128];
199 
200  // Create Epson IMU Data Log
201  sprintf(EpsonlogName, "EpsonLog_%s_%4d-%02d-%02d_T%02d-%02d-%02d.csv",
202  prod_id, tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday, tm.tm_hour,
203  tm.tm_min, tm.tm_sec);
204  FILE *EpsonLog = fopen(EpsonlogName, "w");
205  fprintf(EpsonLog, "#PRODUCT_ID: %s", prod_id);
206  fprintf(EpsonLog, "\r\n#SERIAL_ID: %s", ser_id);
207  fprintf(EpsonLog, "\r\n#Date: %s", ctime(&date));
208  printf("\r\n...Epson IMU Logging.\r\n");
209  sensorStart();
210  printHeaderRow(EpsonLog, &epson_options);
211 
212  unsigned int sample = 0;
213  while (sample < (NUM_SAMPLES - 1)) {
214  if (sensorDataReadBurstNOptions(&epson_sensor, &epson_options,
215  &epson_data) == OK) {
216  printSensorRow(EpsonLog, &epson_options, &epson_data, sample);
217  sample++;
218  }
219  }
220 
221  const time_t end =
222  time(NULL); // Functions for obtaining and printing time and data
223  fprintf(EpsonLog, "\r\n#End: ");
224  fprintf(EpsonLog, "%s", ctime(&end));
225 
226  sensorStop();
227  seDelayMS(1000);
228 
229 #ifdef SPI
230  spiRelease();
231 #else
232  uartRelease();
233 #endif
234 
235  gpioRelease();
236  seRelease();
237  fclose(EpsonLog);
238  printf("\r\n");
239  return 0;
240 }
main
int main(int argc, char *argv[])
Definition: main_csvlogger.c:47
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_csvlogger.c:45
EpsonOptions
Definition: sensor_epsonCommon.h:340
gpioInit
int gpioInit(void)
Definition: hcl_gpio.c:32
hcl.h
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
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
IMUSERIAL
const char * IMUSERIAL
Definition: main_csvlogger.c:41
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