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


ess_imu_ros1_uart_driver
Author(s):
autogenerated on Sun Jun 4 2023 02:59:29