From 570858d87c016841610ef71bfe2a9184c1f319b9 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 23 Apr 2013 22:41:44 +0200 Subject: [PATCH 01/89] General cleanup based on the pull request from muggenhor --- apps/hott_telemetry/hott_telemetry_main.c | 117 +++++++++------------- apps/hott_telemetry/messages.c | 17 ++-- apps/hott_telemetry/messages.h | 20 ++-- 3 files changed, 68 insertions(+), 86 deletions(-) diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c index 31c9247aa5..3e147d8292 100644 --- a/apps/hott_telemetry/hott_telemetry_main.c +++ b/apps/hott_telemetry/hott_telemetry_main.c @@ -53,6 +53,7 @@ #include #include #include +#include #include #include "messages.h" @@ -66,56 +67,44 @@ static int thread_should_exit = false; /**< Deamon exit flag */ static int thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ -static char *daemon_name = "hott_telemetry"; -static char *commandline_usage = "usage: hott_telemetry start|status|stop [-d ]"; +static const char daemon_name[] = "hott_telemetry"; +static const char commandline_usage[] = "usage: hott_telemetry start|status|stop [-d ]"; - -/* A little console messaging experiment - console helper macro */ -#define FATAL_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg); exit(1); -#define ERROR_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg); -#define INFO_MSG(_msg) printf("[%s] %s\n", daemon_name, _msg); /** * Deamon management function. */ __EXPORT int hott_telemetry_main(int argc, char *argv[]); /** - * Mainloop of deamon. + * Mainloop of daemon. */ int hott_telemetry_thread_main(int argc, char *argv[]); -static int read_data(int uart, int *id); -static int send_data(int uart, uint8_t *buffer, int size); +static int recv_req_id(int uart, uint8_t *id); +static int send_data(int uart, uint8_t *buffer, size_t size); -static int open_uart(const char *device, struct termios *uart_config_original) +static int +open_uart(const char *device, struct termios *uart_config_original) { /* baud rate */ - int speed = B19200; - int uart; + static const speed_t speed = B19200; /* open uart */ - uart = open(device, O_RDWR | O_NOCTTY); + const int uart = open(device, O_RDWR | O_NOCTTY); if (uart < 0) { - char msg[80]; - sprintf(msg, "Error opening port: %s\n", device); - FATAL_MSG(msg); + err(1, "Error opening port: %s", device); } - - /* Try to set baud rate */ - struct termios uart_config; + + /* Back up the original uart configuration to restore it after exit */ int termios_state; - - /* Back up the original uart configuration to restore it after exit */ - char msg[80]; - if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - sprintf(msg, "Error getting baudrate / termios config for %s: %d\n", device, termios_state); close(uart); - FATAL_MSG(msg); + err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state); } /* Fill the struct for the new configuration */ + struct termios uart_config; tcgetattr(uart, &uart_config); /* Clear ONLCR flag (which appends a CR for every LF) */ @@ -123,16 +112,14 @@ static int open_uart(const char *device, struct termios *uart_config_original) /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - sprintf(msg, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", - device, termios_state); close(uart); - FATAL_MSG(msg); + err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", + device, termios_state); } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - sprintf(msg, "Error setting baudrate / termios config for %s (tcsetattr)\n", device); close(uart); - FATAL_MSG(msg); + err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device); } /* Activate single wire mode */ @@ -141,18 +128,19 @@ static int open_uart(const char *device, struct termios *uart_config_original) return uart; } -int read_data(int uart, int *id) +int +recv_req_id(int uart, uint8_t *id) { - const int timeout = 1000; + static const int timeout_ms = 1000; // TODO make it a define struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; - char mode; + uint8_t mode; - if (poll(fds, 1, timeout) > 0) { + if (poll(fds, 1, timeout_ms) > 0) { /* Get the mode: binary or text */ - read(uart, &mode, 1); + read(uart, &mode, sizeof(mode)); /* Read the device ID being polled */ - read(uart, id, 1); + read(uart, id, sizeof(*id)); /* if we have a binary mode request */ if (mode != BINARY_MODE_REQUEST_ID) { @@ -160,20 +148,21 @@ int read_data(int uart, int *id) } } else { - ERROR_MSG("UART timeout on TX/RX port"); + warnx("UART timeout on TX/RX port"); return ERROR; } return OK; } -int send_data(int uart, uint8_t *buffer, int size) +int +send_data(int uart, uint8_t *buffer, size_t size) { usleep(POST_READ_DELAY_IN_USECS); uint16_t checksum = 0; - for (int i = 0; i < size; i++) { + for (size_t i = 0; i < size; i++) { if (i == size - 1) { /* Set the checksum: the first uint8_t is taken as the checksum. */ buffer[i] = checksum & 0xff; @@ -182,7 +171,7 @@ int send_data(int uart, uint8_t *buffer, int size) checksum += buffer[i]; } - write(uart, &buffer[i], 1); + write(uart, &buffer[i], sizeof(buffer[i])); /* Sleep before sending the next byte. */ usleep(POST_WRITE_DELAY_IN_USECS); @@ -196,13 +185,14 @@ int send_data(int uart, uint8_t *buffer, int size) return OK; } -int hott_telemetry_thread_main(int argc, char *argv[]) +int +hott_telemetry_thread_main(int argc, char *argv[]) { - INFO_MSG("starting"); + warnx("starting"); thread_running = true; - char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ + const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ /* read commandline arguments */ for (int i = 0; i < argc && argv[i]; i++) { @@ -212,31 +202,28 @@ int hott_telemetry_thread_main(int argc, char *argv[]) } else { thread_running = false; - ERROR_MSG("missing parameter to -d"); - ERROR_MSG(commandline_usage); - exit(1); + errx(1, "missing parameter to -d\n%s", commandline_usage); } } } /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ struct termios uart_config_original; - int uart = open_uart(device, &uart_config_original); + const int uart = open_uart(device, &uart_config_original); if (uart < 0) { - ERROR_MSG("Failed opening HoTT UART, exiting."); + errx(1, "Failed opening HoTT UART, exiting."); thread_running = false; - exit(ERROR); } messages_init(); uint8_t buffer[MESSAGE_BUFFER_SIZE]; - int size = 0; - int id = 0; + size_t size = 0; + uint8_t id = 0; while (!thread_should_exit) { - if (read_data(uart, &id) == OK) { + if (recv_req_id(uart, &id) == OK) { switch (id) { case ELECTRIC_AIR_MODULE: build_eam_response(buffer, &size); @@ -250,7 +237,7 @@ int hott_telemetry_thread_main(int argc, char *argv[]) } } - INFO_MSG("exiting"); + warnx("exiting"); close(uart); @@ -262,23 +249,22 @@ int hott_telemetry_thread_main(int argc, char *argv[]) /** * Process command line arguments and tart the daemon. */ -int hott_telemetry_main(int argc, char *argv[]) +int +hott_telemetry_main(int argc, char *argv[]) { if (argc < 1) { - ERROR_MSG("missing command"); - ERROR_MSG(commandline_usage); - exit(1); + errx(1, "missing command\n%s", commandline_usage); } if (!strcmp(argv[1], "start")) { if (thread_running) { - INFO_MSG("deamon already running"); + warnx("deamon already running"); exit(0); } thread_should_exit = false; - deamon_task = task_spawn("hott_telemetry", + deamon_task = task_spawn(daemon_name, SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, 2048, @@ -294,19 +280,14 @@ int hott_telemetry_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - INFO_MSG("daemon is running"); + warnx("daemon is running"); } else { - INFO_MSG("daemon not started"); + warnx("daemon not started"); } exit(0); } - ERROR_MSG("unrecognized command"); - ERROR_MSG(commandline_usage); - exit(1); + errx(1, "unrecognized command\n%s", commandline_usage); } - - - diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index 8bfb997737..c1988cd054 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -48,27 +48,26 @@ static int battery_sub = -1; static int sensor_sub = -1; -void messages_init(void) +void +messages_init(void) { battery_sub = orb_subscribe(ORB_ID(battery_status)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); } -void build_eam_response(uint8_t *buffer, int *size) +void +build_eam_response(uint8_t *buffer, size_t *size) { /* get a local copy of the current sensor values */ - struct sensor_combined_s raw; - memset(&raw, 0, sizeof(raw)); + struct sensor_combined_s raw = { 0 }; orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); /* get a local copy of the battery data */ - struct battery_status_s battery; - memset(&battery, 0, sizeof(battery)); + struct battery_status_s battery = { 0 }; orb_copy(ORB_ID(battery_status), battery_sub, &battery); - struct eam_module_msg msg; + struct eam_module_msg msg = { 0 }; *size = sizeof(msg); - memset(&msg, 0, *size); msg.start = START_BYTE; msg.eam_sensor_id = ELECTRIC_AIR_MODULE; @@ -84,4 +83,4 @@ void build_eam_response(uint8_t *buffer, int *size) msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); -} \ No newline at end of file +} diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h index 44001e04f0..9ca205f818 100644 --- a/apps/hott_telemetry/messages.h +++ b/apps/hott_telemetry/messages.h @@ -43,11 +43,6 @@ #include -/* The buffer size used to store messages. This must be at least as big as the number of - * fields in the largest message struct. - */ -#define MESSAGE_BUFFER_SIZE 50 - /* The HoTT receiver demands a minimum 5ms period of silence after delivering its request. * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting * the message after the read which takes some milliseconds. @@ -71,12 +66,12 @@ /* The Electric Air Module message. */ struct eam_module_msg { uint8_t start; /**< Start byte */ - uint8_t eam_sensor_id; /**< EAM sensor ID */ + uint8_t eam_sensor_id; /**< EAM sensor */ uint8_t warning; - uint8_t sensor_id; /**< Sensor ID, why different? */ + uint8_t sensor_id; /**< Sensor ID, why different? */ uint8_t alarm_inverse1; uint8_t alarm_inverse2; - uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ + uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ uint8_t cell2_L; uint8_t cell3_L; uint8_t cell4_L; @@ -117,7 +112,14 @@ struct eam_module_msg { uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ }; +/** + * The maximum buffer size required to store a HoTT message. + */ +#define MESSAGE_BUFFER_SIZE sizeof(union { \ + struct eam_module_msg eam; \ +}) + void messages_init(void); -void build_eam_response(uint8_t *buffer, int *size); +void build_eam_response(uint8_t *buffer, size_t *size); #endif /* MESSAGES_H_ */ From 443c3f67d3cdfbbf9a2d16a9c126171ed316051c Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 25 Apr 2013 08:36:14 +0200 Subject: [PATCH 02/89] Reformatting. --- apps/hott_telemetry/messages.c | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index c1988cd054..0b863c6895 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -45,6 +45,9 @@ #include #include +/* The board is very roughly 5 deg warmer than the surrounding air */ +#define BOARD_TEMP_OFFSET_DEG 5 + static int battery_sub = -1; static int sensor_sub = -1; @@ -72,14 +75,20 @@ build_eam_response(uint8_t *buffer, size_t *size) msg.start = START_BYTE; msg.eam_sensor_id = ELECTRIC_AIR_MODULE; msg.sensor_id = EAM_SENSOR_ID; + msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); - msg.temperature2 = TEMP_ZERO_CELSIUS; + msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; + msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10); uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500); msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + // TODO: flight time + // TODO: climb rate + + msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); From b666bbb55c83979d220d26e70a0aaa6f8e908095 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 25 Apr 2013 20:18:06 +0200 Subject: [PATCH 03/89] First steps to supporting GPS --- apps/hott_telemetry/messages.h | 99 ++++++++++++++++++++++++++++------ 1 file changed, 82 insertions(+), 17 deletions(-) diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h index 9ca205f818..8b0935e06d 100644 --- a/apps/hott_telemetry/messages.h +++ b/apps/hott_telemetry/messages.h @@ -65,13 +65,13 @@ /* The Electric Air Module message. */ struct eam_module_msg { - uint8_t start; /**< Start byte */ - uint8_t eam_sensor_id; /**< EAM sensor */ + uint8_t start; /**< Start byte */ + uint8_t eam_sensor_id; /**< EAM sensor */ uint8_t warning; - uint8_t sensor_id; /**< Sensor ID, why different? */ + uint8_t sensor_id; /**< Sensor ID, why different? */ uint8_t alarm_inverse1; uint8_t alarm_inverse2; - uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ + uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ uint8_t cell2_L; uint8_t cell3_L; uint8_t cell4_L; @@ -89,27 +89,27 @@ struct eam_module_msg { uint8_t batt1_voltage_H; uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */ uint8_t batt2_voltage_H; - uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ + uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ uint8_t temperature2; - uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ + uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ uint8_t altitude_H; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ + uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ uint8_t current_H; - uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ + uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ uint8_t main_voltage_H; - uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */ + uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */ uint8_t battery_capacity_H; - uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ + uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ uint8_t climbrate_H; - uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ + uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ + uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ uint8_t rpm_H; - uint8_t electric_min; /**< Flight time in minutes. */ - uint8_t electric_sec; /**< Flight time in seconds. */ - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ + uint8_t electric_min; /**< Flight time in minutes. */ + uint8_t electric_sec; /**< Flight time in seconds. */ + uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ }; /** @@ -119,7 +119,72 @@ struct eam_module_msg { struct eam_module_msg eam; \ }) +/* GPS sensor constants. */ +#define GPS_SENSOR_ID 0x8A +#define GPS_SENSOR_TEXT_ID 0xA0 + +/* The GPS sensor message */ +/* Struct based on: https://code.google.com/p/diy-hott-gps/downloads */ +struct gps_module_msg = { + uint8_t start; /**< Start byte */ + uint8_t gps_sensor_id; /**< EAM sensor */ + uint8_t warning; /**< Byte 3: 0…= warning beeps */ + uint8_t sensor_id; /**< Sensor ID, why different? */ + uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ + uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ + uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ + uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */ + uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */ + + uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */ + uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */ + uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */ + uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */ + uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ + + uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ + uint8_t longitude_in_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ + uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ + uint8_t longitude_sec_L /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ + uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ + + uint8_t distance_L /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ + uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ + uint8_t altitude_L /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ + uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ + uint8_t resolution_L /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ + uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ + uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ + uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ + uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ + uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */ + uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ + uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ + uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ + uint8_t gyro_x_L /**< Byte 33: gyro x low byte (2 bytes) */ + uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ + uint8_t gyro_y_L /**< Byte 35: gyro y low byte (2 bytes) */ + uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ + uint8_t gyro_z_L /**< Byte 37: gyro z low byte (2 bytes) */ + uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ + uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ + uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ + uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */ + uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */ + uint8_t version; /**< Byte 43: 00 version number */ + uint8_t stop; /**< Byte 44: 0x7D Ende byte */ + uint8_t checksum; /**< Byte 45: Parity Byte */ +}; + +/** + * The maximum buffer size required to store a HoTT message. + */ +#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ + struct gps_module_msg gps; \ +}) + void messages_init(void); void build_eam_response(uint8_t *buffer, size_t *size); +void build_gps_response(uint8_t *buffer, size_t *size); #endif /* MESSAGES_H_ */ From 0af9b60db7c9de7b59aa8378980e4dc55a10a051 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 26 Apr 2013 22:28:31 +0200 Subject: [PATCH 04/89] More changes. --- apps/hott_telemetry/messages.c | 26 ++++++++++++++++++++++++-- apps/hott_telemetry/messages.h | 4 ++-- 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index 0b863c6895..db76fa5ace 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -73,8 +73,8 @@ build_eam_response(uint8_t *buffer, size_t *size) *size = sizeof(msg); msg.start = START_BYTE; - msg.eam_sensor_id = ELECTRIC_AIR_MODULE; - msg.sensor_id = EAM_SENSOR_ID; + msg.eam_sensor_id = EAM_SENSOR_ID; + msg.sensor_id = EAM_SENSOR_TEXT_ID; msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; @@ -89,6 +89,28 @@ build_eam_response(uint8_t *buffer, size_t *size) // TODO: climb rate + msg.stop = STOP_BYTE; + + memcpy(buffer, &msg, *size); +} + +void +build_gps_response(uint8_t *buffer, size_t *size) +{ + /* get a local copy of the current sensor values */ + struct sensor_combined_s raw = { 0 }; + orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + + + struct gps_module_msg msg = { 0 }; + *size = sizeof(msg); + + msg.start = START_BYTE; + msg.eam_sensor_id = GPS_SENSOR_ID; + msg.sensor_id = GPS_SENSOR_TEXT_ID; + + // TODO(sjwilks): Complete. + msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h index 8b0935e06d..8ba324f960 100644 --- a/apps/hott_telemetry/messages.h +++ b/apps/hott_telemetry/messages.h @@ -60,8 +60,8 @@ #define TEMP_ZERO_CELSIUS 0x14 /* Electric Air Module (EAM) constants. */ -#define ELECTRIC_AIR_MODULE 0x8e -#define EAM_SENSOR_ID 0xe0 +#define EAM_SENSOR_ID 0x8e +#define EAM_SENSOR_TEXT_ID 0xe0 /* The Electric Air Module message. */ struct eam_module_msg { From 5ebd78345cf815689117af73bc7909145ba71e4c Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Wed, 1 May 2013 21:30:11 +0200 Subject: [PATCH 05/89] Add some GPS data to telemetry message. --- apps/hott_telemetry/hott_telemetry_main.c | 6 ++++- apps/hott_telemetry/messages.c | 23 +++++++++++++++++-- apps/hott_telemetry/messages.h | 28 ++++++++++++----------- 3 files changed, 41 insertions(+), 16 deletions(-) diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c index 3e147d8292..33b721962b 100644 --- a/apps/hott_telemetry/hott_telemetry_main.c +++ b/apps/hott_telemetry/hott_telemetry_main.c @@ -225,7 +225,11 @@ hott_telemetry_thread_main(int argc, char *argv[]) while (!thread_should_exit) { if (recv_req_id(uart, &id) == OK) { switch (id) { - case ELECTRIC_AIR_MODULE: + case EAM_SENSOR_ID: + build_eam_response(buffer, &size); + break; + + case GPS_SENSOR_ID: build_eam_response(buffer, &size); break; diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index db76fa5ace..2e1a5c064e 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -44,17 +44,20 @@ #include #include #include +#include /* The board is very roughly 5 deg warmer than the surrounding air */ #define BOARD_TEMP_OFFSET_DEG 5 static int battery_sub = -1; +static int gps_sub = -1; static int sensor_sub = -1; void messages_init(void) { battery_sub = orb_subscribe(ORB_ID(battery_status)); + gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); } @@ -101,14 +104,30 @@ build_gps_response(uint8_t *buffer, size_t *size) struct sensor_combined_s raw = { 0 }; orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + /* get a local copy of the battery data */ + struct vehicle_gps_position_s gps = { 0 }; + orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); struct gps_module_msg msg = { 0 }; *size = sizeof(msg); msg.start = START_BYTE; - msg.eam_sensor_id = GPS_SENSOR_ID; - msg.sensor_id = GPS_SENSOR_TEXT_ID; + msg.sensor_id = GPS_SENSOR_ID; + msg.sensor_text_id = GPS_SENSOR_TEXT_ID; + + uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); + msg.gps_speed_L = (uint8_t)speed & 0xff; + msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; + uint16_t alt = (uint16_t)(gps.alt); + msg.altitude_L = (uint8_t)alt & 0xff; + msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + + msg.gps_num_sat = gps.satellites_visible; + + /* Display the fix type: 0 = none, 2 = 2D, 3 = 3D */ + msg.gps_fix = (uint8_t)(gps.fix_type + 48); + // TODO(sjwilks): Complete. msg.stop = STOP_BYTE; diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h index 8ba324f960..c83672c08f 100644 --- a/apps/hott_telemetry/messages.h +++ b/apps/hott_telemetry/messages.h @@ -123,13 +123,15 @@ struct eam_module_msg { #define GPS_SENSOR_ID 0x8A #define GPS_SENSOR_TEXT_ID 0xA0 -/* The GPS sensor message */ -/* Struct based on: https://code.google.com/p/diy-hott-gps/downloads */ -struct gps_module_msg = { +/** + * The GPS sensor message + * Struct based on: https://code.google.com/p/diy-hott-gps/downloads + */ +struct gps_module_msg { uint8_t start; /**< Start byte */ - uint8_t gps_sensor_id; /**< EAM sensor */ + uint8_t sensor_id; /**< GPS sensor ID*/ uint8_t warning; /**< Byte 3: 0…= warning beeps */ - uint8_t sensor_id; /**< Sensor ID, why different? */ + uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ @@ -143,16 +145,16 @@ struct gps_module_msg = { uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ - uint8_t longitude_in_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ + uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ - uint8_t longitude_sec_L /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ + uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ - uint8_t distance_L /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ + uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ - uint8_t altitude_L /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ + uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ - uint8_t resolution_L /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ + uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ @@ -161,11 +163,11 @@ struct gps_module_msg = { uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ - uint8_t gyro_x_L /**< Byte 33: gyro x low byte (2 bytes) */ + uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */ uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ - uint8_t gyro_y_L /**< Byte 35: gyro y low byte (2 bytes) */ + uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */ uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ - uint8_t gyro_z_L /**< Byte 37: gyro z low byte (2 bytes) */ + uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */ uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ From 09e60893df954fe69a32a7ebfc54fbb715f61197 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 9 May 2013 09:37:42 +0400 Subject: [PATCH 06/89] gpio_led app added --- apps/gpio_led/Makefile | 42 +++++++ apps/gpio_led/gpio_led_main.c | 184 +++++++++++++++++++++++++++++ nuttx/configs/px4fmu/nsh/appconfig | 1 + 3 files changed, 227 insertions(+) create mode 100644 apps/gpio_led/Makefile create mode 100644 apps/gpio_led/gpio_led_main.c diff --git a/apps/gpio_led/Makefile b/apps/gpio_led/Makefile new file mode 100644 index 0000000000..e9dc219ea9 --- /dev/null +++ b/apps/gpio_led/Makefile @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (C) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Makefile to build gpio_led +# + +APPNAME = gpio_led +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +include $(APPDIR)/mk/app.mk diff --git a/apps/gpio_led/gpio_led_main.c b/apps/gpio_led/gpio_led_main.c new file mode 100644 index 0000000000..c0ad84da1f --- /dev/null +++ b/apps/gpio_led/gpio_led_main.c @@ -0,0 +1,184 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file gpio_led.c + * + * Drive status LED via GPIO. + * + * @author Anton Babushkin + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static bool thread_should_exit = false; +static bool thread_running = false; + +__EXPORT int gpio_led_main(int argc, char *argv[]); + +static int gpio_led_thread_main(int argc, char *argv[]); + +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + fprintf(stderr, "usage: gpio_led {start|stop|status}\n\n"); + exit(1); +} + +int gpio_led_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("gpio_led already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + task_spawn("gpio_led", + SCHED_DEFAULT, + SCHED_PRIORITY_MIN, + 2048, + gpio_led_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + printf("\tgpio_led is running\n"); + } else { + printf("\tgpio_led not started\n"); + } + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int gpio_led_thread_main(int argc, char *argv[]) +{ + /* welcome user */ + printf("[gpio_led] started\n"); + + int fd = open(GPIO_DEVICE_PATH, 0); + if (fd < 0) { + printf("[gpio_led] GPIO: open fail\n"); + return ERROR; + } + + /* set GPIO EXT 1 as output */ + ioctl(fd, GPIO_SET_OUTPUT, GPIO_EXT_1); + + ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); + + /* initialize values */ + bool led_state = false; + int counter = 0; + + /* subscribe to vehicle status topic */ + struct vehicle_status_s status; + memset(&status, 0, sizeof(status)); + int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); + + while (!thread_should_exit) { + bool status_updated; + orb_check((vehicle_status_sub), &status_updated); + if (status_updated) + orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &status); + + int pattern = 0; + if (status.flag_system_armed) { + if (status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { + pattern = 0x3f; // ****** solid (armed) + } else { + pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning) + } + } else { + if (status.state_machine == SYSTEM_STATE_PREFLIGHT) { + pattern = 0x00; // ______ off (disarmed, preflight check) + } else if (status.state_machine == SYSTEM_STATE_STANDBY && status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { + pattern = 0x38; // ***___ slow blink (disarmed, ready) + } else { + pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm) + } + } + + bool led_state_new = (pattern & (1 << counter)) != 0; + if (led_state_new != led_state) { + led_state = led_state_new; + if (led_state) { + ioctl(fd, GPIO_SET, GPIO_EXT_1); + } else { + ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); + } + } + + counter++; + if (counter > 5) + counter = 0; + + usleep(333333); // sleep ~1/3s + } + + ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); + + printf("[gpio_led] exiting\n"); + + return 0; +} diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 82ab94be78..e0ad9fb1ad 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -103,6 +103,7 @@ CONFIGURED_APPS += fixedwing_pos_control CONFIGURED_APPS += position_estimator CONFIGURED_APPS += attitude_estimator_ekf CONFIGURED_APPS += hott_telemetry +CONFIGURED_APPS += gpio_led endif # Hacking tools From 0489595e7f34f4bacc1b63f31eed5e64fe55c7e6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 9 May 2013 19:44:09 +0400 Subject: [PATCH 07/89] Use work_queue instead of thread --- apps/gpio_led/gpio_led_main.c | 196 +++++++++++++++------------------- 1 file changed, 86 insertions(+), 110 deletions(-) diff --git a/apps/gpio_led/gpio_led_main.c b/apps/gpio_led/gpio_led_main.c index c0ad84da1f..64ede01c31 100644 --- a/apps/gpio_led/gpio_led_main.c +++ b/apps/gpio_led/gpio_led_main.c @@ -45,140 +45,116 @@ #include #include #include -#include +#include +#include #include #include #include #include #include -static bool thread_should_exit = false; -static bool thread_running = false; + +struct gpio_led_s +{ + struct work_s work; + int gpio_fd; + struct vehicle_status_s status; + int vehicle_status_sub; + bool led_state; + int counter; +}; + +static struct gpio_led_s gpio_led; __EXPORT int gpio_led_main(int argc, char *argv[]); -static int gpio_led_thread_main(int argc, char *argv[]); +void gpio_led_start(FAR void *arg); -static void usage(const char *reason); - -static void -usage(const char *reason) -{ - if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: gpio_led {start|stop|status}\n\n"); - exit(1); -} +void gpio_led_cycle(FAR void *arg); int gpio_led_main(int argc, char *argv[]) { - if (argc < 1) - usage("missing command"); - - if (!strcmp(argv[1], "start")) { - - if (thread_running) { - printf("gpio_led already running\n"); - /* this is not an error */ - exit(0); - } - - thread_should_exit = false; - task_spawn("gpio_led", - SCHED_DEFAULT, - SCHED_PRIORITY_MIN, - 2048, - gpio_led_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); - exit(0); + memset(&gpio_led, 0, sizeof(gpio_led)); + int ret = work_queue(LPWORK, &gpio_led.work, gpio_led_start, &gpio_led, 0); + if (ret != 0) { + printf("[gpio_led] Failed to queue work: %d\n", ret); + exit(1); } - - if (!strcmp(argv[1], "stop")) { - thread_should_exit = true; - exit(0); - } - - if (!strcmp(argv[1], "status")) { - if (thread_running) { - printf("\tgpio_led is running\n"); - } else { - printf("\tgpio_led not started\n"); - } - exit(0); - } - - usage("unrecognized command"); - exit(1); + exit(0); } -int gpio_led_thread_main(int argc, char *argv[]) +void gpio_led_start(FAR void *arg) { - /* welcome user */ - printf("[gpio_led] started\n"); + FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg; - int fd = open(GPIO_DEVICE_PATH, 0); - if (fd < 0) { + /* open GPIO device */ + priv->gpio_fd = open(GPIO_DEVICE_PATH, 0); + if (priv->gpio_fd < 0) { printf("[gpio_led] GPIO: open fail\n"); - return ERROR; + return; } - /* set GPIO EXT 1 as output */ - ioctl(fd, GPIO_SET_OUTPUT, GPIO_EXT_1); - - ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); - - /* initialize values */ - bool led_state = false; - int counter = 0; + /* configure GPIO pin */ + ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, GPIO_EXT_1); /* subscribe to vehicle status topic */ - struct vehicle_status_s status; - memset(&status, 0, sizeof(status)); - int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); + memset(&priv->status, 0, sizeof(priv->status)); + priv->vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); - while (!thread_should_exit) { - bool status_updated; - orb_check((vehicle_status_sub), &status_updated); - if (status_updated) - orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &status); - - int pattern = 0; - if (status.flag_system_armed) { - if (status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { - pattern = 0x3f; // ****** solid (armed) - } else { - pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning) - } - } else { - if (status.state_machine == SYSTEM_STATE_PREFLIGHT) { - pattern = 0x00; // ______ off (disarmed, preflight check) - } else if (status.state_machine == SYSTEM_STATE_STANDBY && status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { - pattern = 0x38; // ***___ slow blink (disarmed, ready) - } else { - pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm) - } - } - - bool led_state_new = (pattern & (1 << counter)) != 0; - if (led_state_new != led_state) { - led_state = led_state_new; - if (led_state) { - ioctl(fd, GPIO_SET, GPIO_EXT_1); - } else { - ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); - } - } - - counter++; - if (counter > 5) - counter = 0; - - usleep(333333); // sleep ~1/3s + /* add worker to queue */ + int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0); + if (ret != 0) { + printf("[gpio_led] Failed to queue work: %d\n", ret); + return; } - ioctl(fd, GPIO_CLEAR, GPIO_EXT_1); - - printf("[gpio_led] exiting\n"); - - return 0; + printf("[gpio_led] Started\n"); +} + +void gpio_led_cycle(FAR void *arg) +{ + FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg; + + /* check for status updates*/ + bool status_updated; + orb_check(priv->vehicle_status_sub, &status_updated); + if (status_updated) + orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status); + + /* select pattern for current status */ + int pattern = 0; + if (priv->status.flag_system_armed) { + if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { + pattern = 0x3f; // ****** solid (armed) + } else { + pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning) + } + } else { + if (priv->status.state_machine == SYSTEM_STATE_PREFLIGHT) { + pattern = 0x00; // ______ off (disarmed, preflight check) + } else if (priv->status.state_machine == SYSTEM_STATE_STANDBY && + priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { + pattern = 0x38; // ***___ slow blink (disarmed, ready) + } else { + pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm) + } + } + + /* blink pattern */ + bool led_state_new = (pattern & (1 << priv->counter)) != 0; + if (led_state_new != priv->led_state) { + priv->led_state = led_state_new; + if (led_state_new) { + ioctl(priv->gpio_fd, GPIO_SET, GPIO_EXT_1); + } else { + ioctl(priv->gpio_fd, GPIO_CLEAR, GPIO_EXT_1); + } + } + + priv->counter++; + if (priv->counter > 5) + priv->counter = 0; + + /* repeat cycle at 5 Hz*/ + work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000)); } From 150eabbf3986bd120908506b97ed7d9e9eed1038 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 14 May 2013 23:53:21 +0200 Subject: [PATCH 08/89] GPS support - mostly working. --- apps/hott_telemetry/hott_telemetry_main.c | 2 +- apps/hott_telemetry/messages.c | 87 +++++++++++++++++++++-- apps/hott_telemetry/messages.h | 4 +- 3 files changed, 87 insertions(+), 6 deletions(-) diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c index 33b721962b..f419c95ded 100644 --- a/apps/hott_telemetry/hott_telemetry_main.c +++ b/apps/hott_telemetry/hott_telemetry_main.c @@ -230,7 +230,7 @@ hott_telemetry_thread_main(int argc, char *argv[]) break; case GPS_SENSOR_ID: - build_eam_response(buffer, &size); + build_gps_response(buffer, &size); break; default: diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index 2e1a5c064e..feec8998c5 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -39,10 +39,12 @@ #include "messages.h" +#include #include #include #include #include +#include #include #include @@ -51,6 +53,7 @@ static int battery_sub = -1; static int gps_sub = -1; +static int home_sub = -1; static int sensor_sub = -1; void @@ -58,6 +61,7 @@ messages_init(void) { battery_sub = orb_subscribe(ORB_ID(battery_status)); gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + home_sub = orb_subscribe(ORB_ID(home_position)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); } @@ -115,22 +119,97 @@ build_gps_response(uint8_t *buffer, size_t *size) msg.sensor_id = GPS_SENSOR_ID; msg.sensor_text_id = GPS_SENSOR_TEXT_ID; + /* Current flight direction */ + msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); + + /* GPS speed */ uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); msg.gps_speed_L = (uint8_t)speed & 0xff; msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; - uint16_t alt = (uint16_t)(gps.alt); + /* Get latitude in degrees, minutes and seconds */ + double lat = ((double)(gps.lat)) * 1e-7d; + + msg.latitude_ns = 0; + if (lat < 0) { + msg.latitude_ns = 1; + lat = -lat; + } + + int deg; + int min; + int sec; + convert_to_degrees_minutes_seconds(lat, °, &min, &sec); + + uint16_t lat_min = (uint16_t)(deg * 100 + min); + msg.latitude_min_L = (uint8_t)lat_min & 0xff; + msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff; + uint16_t lat_sec = (uint16_t)(sec); + msg.latitude_sec_L = (uint8_t)lat_sec & 0xff; + msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff; + + + /* Get longitude in degrees, minutes and seconds */ + double lon = ((double)(gps.lon)) * 1e-7d; + + msg.longitude_ew = 0; + if (lon < 0) { + msg.longitude_ew = 1; + lon = -lon; + } + + convert_to_degrees_minutes_seconds(lon, °, &min, &sec); + + uint16_t lon_min = (uint16_t)(deg * 100 + min); + msg.longitude_min_L = (uint8_t)lon_min & 0xff; + msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff; + uint16_t lon_sec = (uint16_t)(sec); + msg.longitude_sec_L = (uint8_t)lon_sec & 0xff; + msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; + + /* Altitude */ + uint16_t alt = (uint16_t)(gps.alt * 1e-3 + 500.0f); msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + /* Distance from home */ + bool updated; + orb_check(home_sub, &updated); + if (updated) { + /* get a local copy of the home position data */ + struct home_position_s home = { 0 }; + orb_copy(ORB_ID(home_position), home_sub, &home); + + uint16_t dist = (uint16_t)get_distance_to_next_waypoint( + (double)home.lat*1e-7, (double)home.lon*1e-7, lat, lon); + warnx("dist %d home.lat %3.6f home.lon %3.6f lat %3.6f lon %3.6f ", + dist, (double)home.lat*1e-7d, (double)home.lon*1e-7d, lat, lon); + msg.distance_L = (uint8_t)dist & 0xff; + msg.distance_H = (uint8_t)(dist >> 8) & 0xff; + + /* Direction back to home */ + uint16_t bearing = (uint16_t)get_bearing_to_next_waypoint( + (double)home.lat*1e-7, (double)home.lon*1e-7, lat, lon) * M_RAD_TO_DEG_F; + msg.home_direction = (uint8_t)bearing >> 1; + } + msg.gps_num_sat = gps.satellites_visible; - /* Display the fix type: 0 = none, 2 = 2D, 3 = 3D */ + /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */ + msg.gps_fix_char = (uint8_t)(gps.fix_type + 48); msg.gps_fix = (uint8_t)(gps.fix_type + 48); - // TODO(sjwilks): Complete. - msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); } + +void +convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec) +{ + *deg = (int)val; + + double delta = val - *deg; + *min = (int)(delta * 60.0); + *sec = (int)(delta * 3600.0); +} diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h index c83672c08f..4ccc1b3114 100644 --- a/apps/hott_telemetry/messages.h +++ b/apps/hott_telemetry/messages.h @@ -145,7 +145,7 @@ struct gps_module_msg { uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ - uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ + uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ @@ -188,5 +188,7 @@ struct gps_module_msg { void messages_init(void); void build_eam_response(uint8_t *buffer, size_t *size); void build_gps_response(uint8_t *buffer, size_t *size); +void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); + #endif /* MESSAGES_H_ */ From 58084685b2b2f8e31598320318a7c34dd0a96955 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 16 May 2013 09:12:13 +0200 Subject: [PATCH 09/89] Hotfix: Changed alarms back to what they originally were designed for: Traps to later see if condition was once violated. Currente status can be read through the status flags --- src/drivers/px4io/px4io.cpp | 3 +++ src/modules/px4iofirmware/controls.c | 3 +-- src/modules/px4iofirmware/mixer.cpp | 1 - src/modules/px4iofirmware/registers.c | 1 - 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index a40142792a..8b2fae12b8 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1273,6 +1273,9 @@ PX4IO::print_status() ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""), ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""), ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : "")); + /* now clear alarms */ + io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, 0xFFFF); + printf("vbatt %u ibatt %u vbatt scale %u\n", io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT), io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT), diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index dc36f6c934..3cf9ca149b 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -217,9 +217,8 @@ controls_tick() { if (assigned_channels == 0) { rc_input_lost = true; } else { - /* set RC OK flag and clear RC lost alarm */ + /* set RC OK flag */ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK; - r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_RC_LOST; } /* diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 5ada1b220e..1234e2eea5 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -100,7 +100,6 @@ mixer_tick(void) } else { r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK; - r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_FMU_LOST; } source = MIX_FAILSAFE; diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 61049c8b6a..f21ac6e4cc 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -203,7 +203,6 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num system_state.fmu_data_received_time = hrt_absolute_time(); r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK; - r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_FMU_LOST; r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RAW_PWM; break; From 09ce3e2d0a531138c29e1d32f1a9a902b259683d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 May 2013 11:30:50 +0400 Subject: [PATCH 10/89] Added GPIO_EXT1/GPIO_EXT2 selection. --- src/modules/gpio_led/gpio_led.c | 30 +++++++++++++++++++++++------- 1 file changed, 23 insertions(+), 7 deletions(-) diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c index b9b066d24a..83b598e922 100644 --- a/src/modules/gpio_led/gpio_led.c +++ b/src/modules/gpio_led/gpio_led.c @@ -57,13 +57,14 @@ struct gpio_led_s { struct work_s work; int gpio_fd; + int pin; struct vehicle_status_s status; int vehicle_status_sub; bool led_state; int counter; }; -static struct gpio_led_s gpio_led; +static struct gpio_led_s gpio_led_data; __EXPORT int gpio_led_main(int argc, char *argv[]); @@ -73,8 +74,23 @@ void gpio_led_cycle(FAR void *arg); int gpio_led_main(int argc, char *argv[]) { - memset(&gpio_led, 0, sizeof(gpio_led)); - int ret = work_queue(LPWORK, &gpio_led.work, gpio_led_start, &gpio_led, 0); + int pin = GPIO_EXT_1; + if (argc > 1) { + if (!strcmp(argv[1], "-p")) { + if (!strcmp(argv[2], "1")) { + pin = GPIO_EXT_1; + } else if (!strcmp(argv[2], "2")) { + pin = GPIO_EXT_2; + } else { + printf("[gpio_led] Unsupported pin: %s\n", argv[2]); + exit(1); + } + } + } + + memset(&gpio_led_data, 0, sizeof(gpio_led_data)); + gpio_led_data.pin = pin; + int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0); if (ret != 0) { printf("[gpio_led] Failed to queue work: %d\n", ret); exit(1); @@ -94,7 +110,7 @@ void gpio_led_start(FAR void *arg) } /* configure GPIO pin */ - ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, GPIO_EXT_1); + ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, priv->pin); /* subscribe to vehicle status topic */ memset(&priv->status, 0, sizeof(priv->status)); @@ -107,7 +123,7 @@ void gpio_led_start(FAR void *arg) return; } - printf("[gpio_led] Started\n"); + printf("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin); } void gpio_led_cycle(FAR void *arg) @@ -144,9 +160,9 @@ void gpio_led_cycle(FAR void *arg) if (led_state_new != priv->led_state) { priv->led_state = led_state_new; if (led_state_new) { - ioctl(priv->gpio_fd, GPIO_SET, GPIO_EXT_1); + ioctl(priv->gpio_fd, GPIO_SET, priv->pin); } else { - ioctl(priv->gpio_fd, GPIO_CLEAR, GPIO_EXT_1); + ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin); } } From 6e8621269bc032afdb77830cebac01808299263d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 May 2013 13:59:51 +0400 Subject: [PATCH 11/89] Code style fixed --- src/modules/gpio_led/gpio_led.c | 22 +++++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c index 83b598e922..a80bf9cb83 100644 --- a/src/modules/gpio_led/gpio_led.c +++ b/src/modules/gpio_led/gpio_led.c @@ -53,8 +53,7 @@ #include #include -struct gpio_led_s -{ +struct gpio_led_s { struct work_s work; int gpio_fd; int pin; @@ -75,12 +74,15 @@ void gpio_led_cycle(FAR void *arg); int gpio_led_main(int argc, char *argv[]) { int pin = GPIO_EXT_1; + if (argc > 1) { if (!strcmp(argv[1], "-p")) { if (!strcmp(argv[2], "1")) { pin = GPIO_EXT_1; + } else if (!strcmp(argv[2], "2")) { pin = GPIO_EXT_2; + } else { printf("[gpio_led] Unsupported pin: %s\n", argv[2]); exit(1); @@ -91,10 +93,12 @@ int gpio_led_main(int argc, char *argv[]) memset(&gpio_led_data, 0, sizeof(gpio_led_data)); gpio_led_data.pin = pin; int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0); + if (ret != 0) { printf("[gpio_led] Failed to queue work: %d\n", ret); exit(1); } + exit(0); } @@ -104,6 +108,7 @@ void gpio_led_start(FAR void *arg) /* open GPIO device */ priv->gpio_fd = open(GPIO_DEVICE_PATH, 0); + if (priv->gpio_fd < 0) { printf("[gpio_led] GPIO: open fail\n"); return; @@ -118,6 +123,7 @@ void gpio_led_start(FAR void *arg) /* add worker to queue */ int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0); + if (ret != 0) { printf("[gpio_led] Failed to queue work: %d\n", ret); return; @@ -133,23 +139,29 @@ void gpio_led_cycle(FAR void *arg) /* check for status updates*/ bool status_updated; orb_check(priv->vehicle_status_sub, &status_updated); + if (status_updated) orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status); /* select pattern for current status */ int pattern = 0; + if (priv->status.flag_system_armed) { if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { pattern = 0x3f; // ****** solid (armed) + } else { pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning) } + } else { if (priv->status.state_machine == SYSTEM_STATE_PREFLIGHT) { pattern = 0x00; // ______ off (disarmed, preflight check) + } else if (priv->status.state_machine == SYSTEM_STATE_STANDBY && - priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { + priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) { pattern = 0x38; // ***___ slow blink (disarmed, ready) + } else { pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm) } @@ -157,16 +169,20 @@ void gpio_led_cycle(FAR void *arg) /* blink pattern */ bool led_state_new = (pattern & (1 << priv->counter)) != 0; + if (led_state_new != priv->led_state) { priv->led_state = led_state_new; + if (led_state_new) { ioctl(priv->gpio_fd, GPIO_SET, priv->pin); + } else { ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin); } } priv->counter++; + if (priv->counter > 5) priv->counter = 0; From 327d8751d2a4f43849827e78eaab800b2ca09e3f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 22 May 2013 17:53:17 +0200 Subject: [PATCH 12/89] Hotfix: Removing GPS debug output --- src/modules/mavlink/mavlink_receiver.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.c b/src/modules/mavlink/mavlink_receiver.c index a42612f9e4..940d030b2c 100644 --- a/src/modules/mavlink/mavlink_receiver.c +++ b/src/modules/mavlink/mavlink_receiver.c @@ -429,11 +429,11 @@ handle_message(mavlink_message_t *msg) hil_frames += 1 ; // output - if ((timestamp - old_timestamp) > 10000000) { - printf("receiving hil gps at %d hz\n", hil_frames/10); - old_timestamp = timestamp; - hil_frames = 0; - } + // if ((timestamp - old_timestamp) > 10000000) { + // printf("receiving hil gps at %d hz\n", hil_frames/10); + // old_timestamp = timestamp; + // hil_frames = 0; + // } } if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) { From 9f5fee09baaeb4e98e0729e4c0a853ed146ac578 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 May 2013 21:43:23 +0400 Subject: [PATCH 13/89] logconv.py added: convert sdlog binary log to CSV --- Tools/logconv.py | 59 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) create mode 100644 Tools/logconv.py diff --git a/Tools/logconv.py b/Tools/logconv.py new file mode 100644 index 0000000000..c47d22a451 --- /dev/null +++ b/Tools/logconv.py @@ -0,0 +1,59 @@ +#!/usr/bin/env python + +"""Convert binary log generated by sdlog to CSV format + +Usage: python logconv.py """ + +__author__ = "Anton Babushkin" +__version__ = "0.1" + +import struct, sys + +def _unpack_packet(data): + s = "" + s += "Q" #.timestamp = buf.raw.timestamp, + s += "fff" #.gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]}, + s += "fff" #.accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]}, + s += "fff" #.mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]}, + s += "f" #.baro = buf.raw.baro_pres_mbar, + s += "f" #.baro_alt = buf.raw.baro_alt_meter, + s += "f" #.baro_temp = buf.raw.baro_temp_celcius, + s += "ffff" #.control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]}, + s += "ffffffff" #.actuators = {buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3], buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]}, + s += "f" #.vbat = buf.batt.voltage_v, + s += "f" #.bat_current = buf.batt.current_a, + s += "f" #.bat_discharged = buf.batt.discharged_mah, + s += "ffff" #.adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]}, + s += "fff" #.local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z}, + s += "iii" #.gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt}, + s += "fff" #.attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw}, + s += "fffffffff" #.rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]}, + s += "fff" #.vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw}, + s += "ffff" #.control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]}, + s += "ffffff" #.flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality}, + s += "f" #.diff_pressure = buf.diff_pres.differential_pressure_pa, + s += "f" #.ind_airspeed = buf.airspeed.indicated_airspeed_m_s, + s += "f" #.true_airspeed = buf.airspeed.true_airspeed_m_s + s += "iii" # to align to 280 + d = struct.unpack(s, data) + return d + +def _main(): + if len(sys.argv) < 2: + print "Usage:\npython logconv.py " + return + fn = sys.argv[1] + sysvector_size = 280 + f = open(fn, "r") + while True: + data = f.read(sysvector_size) + if len(data) < sysvector_size: + break + a = [] + for i in _unpack_packet(data): + a.append(str(i)) + print ";".join(a) + f.close() + +if __name__ == "__main__": + _main() From 2135628254fa9035c3cbb7db8ed9c05bb3dd172a Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 23 May 2013 00:08:35 +0200 Subject: [PATCH 14/89] Hotfix: dependency scanning for modules was totally broken. Fix it so that changes to depended headers correctly cause modules to be rebuilt. --- makefiles/module.mk | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/makefiles/module.mk b/makefiles/module.mk index 074cd159ae..9e4cbafc9c 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -183,11 +183,16 @@ CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibi # module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES) -## -## Object files we will generate from sources -## +# +# Object files we will generate from sources +# OBJS = $(addsuffix .o,$(SRCS)) +# +# Dependency files that will be auto-generated +# +DEPS = $(addsuffix .d,$(SRCS)) + # # SRCS -> OBJS rules # @@ -219,3 +224,5 @@ $(MODULE_OBJ): $(OBJS) $(GLOBAL_DEPS) clean: $(Q) $(REMOVE) $(MODULE_PRELINK) $(OBJS) + +-include $(DEPS) From 1caddb7bbb53f3017e2ee67742531b2159999658 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 16:11:03 +1000 Subject: [PATCH 15/89] Initial work of so3 nonlinear complementary filter --- .../attitude_estimator_so3_comp_main.cpp | 610 ++++++++++++++++++ .../attitude_estimator_so3_comp_params.c | 44 ++ .../attitude_estimator_so3_comp_params.h | 32 + .../attitude_estimator_so3_comp/module.mk | 8 + 4 files changed, 694 insertions(+) create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h create mode 100644 src/modules/attitude_estimator_so3_comp/module.mk diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp new file mode 100755 index 0000000000..381b0df75c --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -0,0 +1,610 @@ +/* + * @file attitude_estimator_so3_comp_main.c + * + * Nonlinear SO3 filter for Attitude Estimation. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif +#include "attitude_estimator_so3_comp_params.h" +#ifdef __cplusplus +} +#endif + +extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]); + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ +volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame + +/** + * Mainloop of attitude_estimator_so3_comp. + */ +int attitude_estimator_so3_comp_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-p ]\n\n"); + exit(1); +} + +/** + * The attitude_estimator_so3_comp app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int attitude_estimator_so3_comp_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("attitude_estimator_so3_comp already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + attitude_estimator_so3_comp_task = task_spawn("attitude_estimator_so3_comp", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 5, + 12400, + attitude_estimator_so3_comp_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + printf("\tattitude_estimator_so3_comp app is running\n"); + + } else { + printf("\tattitude_estimator_so3_comp app not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +//--------------------------------------------------------------------------------------------------- +// Fast inverse square-root +// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root +float invSqrt(float x) { + float halfx = 0.5f * x; + float y = x; + long i = *(long*)&y; + i = 0x5f3759df - (i>>1); + y = *(float*)&i; + y = y * (1.5f - (halfx * y * y)); + return y; +} + +void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az, float twoKp, float twoKi, float dt) { + float recipNorm; + float halfvx, halfvy, halfvz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) + if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Estimated direction of gravity and vector perpendicular to magnetic flux + halfvx = q1 * q3 - q0 * q2; + halfvy = q0 * q1 + q2 * q3; + halfvz = q0 * q0 - 0.5f + q3 * q3; + + // Error is sum of cross product between estimated and measured direction of gravity + halfex = (ay * halfvz - az * halfvy); + halfey = (az * halfvx - ax * halfvz); + halfez = (ax * halfvy - ay * halfvx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * dt); // pre-multiply common factors + gy *= (0.5f * dt); + gz *= (0.5f * dt); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; +} + +void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { + float recipNorm; + float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float hx, hy, bx, bz; + float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) + if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { + MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); + return; + } + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) + if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + // Reference direction of Earth's magnetic field + hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); + hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + bx = sqrt(hx * hx + hy * hy); + bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; + halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); + halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); + halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); + halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); + halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * dt); // pre-multiply common factors + gy *= (0.5f * dt); + gz *= (0.5f * dt); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; +} + +/* + * [Rot_matrix,x_aposteriori,P_aposteriori] = attitudeKalmanfilter(dt,z_k,x_aposteriori_k,P_aposteriori_k,knownConst) + */ + +/* + * EKF Attitude Estimator main function. + * + * Estimates the attitude recursively once started. + * + * @param argc number of commandline arguments (plus command name) + * @param argv strings containing the arguments + */ +int attitude_estimator_so3_comp_thread_main(int argc, char *argv[]) +{ + +const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds + + float dt = 0.005f; + + /* output euler angles */ + float euler[3] = {0.0f, 0.0f, 0.0f}; + + float Rot_matrix[9] = {1.f, 0, 0, + 0, 1.f, 0, + 0, 0, 1.f + }; /**< init: identity matrix */ + + float acc[3] = {0.0f, 0.0f, 0.0f}; + float gyro[3] = {0.0f, 0.0f, 0.0f}; + float mag[3] = {0.0f, 0.0f, 0.0f}; + + // print text + printf("Nonlinear SO3 Attitude Estimator initialized..\n\n"); + fflush(stdout); + + int overloadcounter = 19; + + /* store start time to guard against too slow update rates */ + uint64_t last_run = hrt_absolute_time(); + + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + struct vehicle_attitude_s att; + memset(&att, 0, sizeof(att)); + struct vehicle_status_s state; + memset(&state, 0, sizeof(state)); + + uint64_t last_data = 0; + uint64_t last_measurement = 0; + + /* subscribe to raw data */ + int sub_raw = orb_subscribe(ORB_ID(sensor_combined)); + /* rate-limit raw data updates to 200Hz */ + orb_set_interval(sub_raw, 4); + + /* subscribe to param changes */ + int sub_params = orb_subscribe(ORB_ID(parameter_update)); + + /* subscribe to system state*/ + int sub_state = orb_subscribe(ORB_ID(vehicle_status)); + + /* advertise attitude */ + orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); + + int loopcounter = 0; + int printcounter = 0; + + thread_running = true; + + /* advertise debug value */ + // struct debug_key_value_s dbg = { .key = "", .value = 0.0f }; + // orb_advert_t pub_dbg = -1; + + float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f}; + // XXX write this out to perf regs + + /* keep track of sensor updates */ + uint32_t sensor_last_count[3] = {0, 0, 0}; + uint64_t sensor_last_timestamp[3] = {0, 0, 0}; + + struct attitude_estimator_so3_comp_params so3_comp_params; + struct attitude_estimator_so3_comp_param_handles so3_comp_param_handles; + + /* initialize parameter handles */ + parameters_init(&so3_comp_param_handles); + + uint64_t start_time = hrt_absolute_time(); + bool initialized = false; + + float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f }; + unsigned offset_count = 0; + + /* register the perf counter */ + perf_counter_t so3_comp_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_so3_comp"); + + /* Main loop*/ + while (!thread_should_exit) { + + struct pollfd fds[2]; + fds[0].fd = sub_raw; + fds[0].events = POLLIN; + fds[1].fd = sub_params; + fds[1].events = POLLIN; + int ret = poll(fds, 2, 1000); + + if (ret < 0) { + /* XXX this is seriously bad - should be an emergency */ + } else if (ret == 0) { + /* check if we're in HIL - not getting sensor data is fine then */ + orb_copy(ORB_ID(vehicle_status), sub_state, &state); + + if (!state.flag_hil_enabled) { + fprintf(stderr, + "[att so3_comp] WARNING: Not getting sensors - sensor app running?\n"); + } + + } else { + + /* only update parameters if they changed */ + if (fds[1].revents & POLLIN) { + /* read from param to clear updated flag */ + struct parameter_update_s update; + orb_copy(ORB_ID(parameter_update), sub_params, &update); + + /* update parameters */ + parameters_update(&so3_comp_param_handles, &so3_comp_params); + } + + /* only run filter if sensor values changed */ + if (fds[0].revents & POLLIN) { + + /* get latest measurements */ + orb_copy(ORB_ID(sensor_combined), sub_raw, &raw); + + if (!initialized) { + + gyro_offsets[0] += raw.gyro_rad_s[0]; + gyro_offsets[1] += raw.gyro_rad_s[1]; + gyro_offsets[2] += raw.gyro_rad_s[2]; + offset_count++; + + if (hrt_absolute_time() - start_time > 3000000LL) { + initialized = true; + gyro_offsets[0] /= offset_count; + gyro_offsets[1] /= offset_count; + gyro_offsets[2] /= offset_count; + } + + } else { + + perf_begin(so3_comp_loop_perf); + + /* Calculate data time difference in seconds */ + dt = (raw.timestamp - last_measurement) / 1000000.0f; + last_measurement = raw.timestamp; + uint8_t update_vect[3] = {0, 0, 0}; + + /* Fill in gyro measurements */ + if (sensor_last_count[0] != raw.gyro_counter) { + update_vect[0] = 1; + sensor_last_count[0] = raw.gyro_counter; + sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]); + sensor_last_timestamp[0] = raw.timestamp; + } + + gyro[0] = raw.gyro_rad_s[0] - gyro_offsets[0]; + gyro[1] = raw.gyro_rad_s[1] - gyro_offsets[1]; + gyro[2] = raw.gyro_rad_s[2] - gyro_offsets[2]; + + /* update accelerometer measurements */ + if (sensor_last_count[1] != raw.accelerometer_counter) { + update_vect[1] = 1; + sensor_last_count[1] = raw.accelerometer_counter; + sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]); + sensor_last_timestamp[1] = raw.timestamp; + } + + acc[0] = raw.accelerometer_m_s2[0]; + acc[1] = raw.accelerometer_m_s2[1]; + acc[2] = raw.accelerometer_m_s2[2]; + + /* update magnetometer measurements */ + if (sensor_last_count[2] != raw.magnetometer_counter) { + update_vect[2] = 1; + sensor_last_count[2] = raw.magnetometer_counter; + sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]); + sensor_last_timestamp[2] = raw.timestamp; + } + + mag[0] = raw.magnetometer_ga[0]; + mag[1] = raw.magnetometer_ga[1]; + mag[2] = raw.magnetometer_ga[2]; + + uint64_t now = hrt_absolute_time(); + unsigned int time_elapsed = now - last_run; + last_run = now; + + if (time_elapsed > loop_interval_alarm) { + //TODO: add warning, cpu overload here + // if (overloadcounter == 20) { + // printf("CPU OVERLOAD DETECTED IN ATTITUDE ESTIMATOR EKF (%lu > %lu)\n", time_elapsed, loop_interval_alarm); + // overloadcounter = 0; + // } + + overloadcounter++; + } + + static bool const_initialized = false; + + /* initialize with good values once we have a reasonable dt estimate */ + if (!const_initialized && dt < 0.05f && dt > 0.005f) { + dt = 0.005f; + parameters_update(&so3_comp_param_handles, &so3_comp_params); + const_initialized = true; + } + + /* do not execute the filter if not initialized */ + if (!const_initialized) { + continue; + } + + uint64_t timing_start = hrt_absolute_time(); + + MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + + float aSq = q0*q0; + float bSq = q1*q1; + float cSq = q2*q2; + float dSq = q3*q3; + + Rot_matrix[0] = aSq + bSq - cSq - dSq; + Rot_matrix[1] = 2.0 * (b * c - a * d); + Rot_matrix[2] = 2.0 * (a * c + b * d); + Rot_matrix[3] = 2.0 * (b * c + a * d); + Rot_matrix[4] = aSq - bSq + cSq - dSq; + Rot_matrix[5] = 2.0 * (c * d - a * b); + Rot_matrix[6] = 2.0 * (b * d - a * c); + Rot_matrix[7] = 2.0 * (a * b + c * d); + Rot_matrix[8] = aSq - bSq - cSq + dSq; + + /* Compute Euler angle */ + float theta = asinf(-Rot_matrix[6]); + euler[1] = theta; + + if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ + euler[0] = 0.0f; + euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); + } else if (fabsf(theta + M_PI_2_F) < 1.0e-3f) { + euler[0] = 0.0f; + euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); + } else { + euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); + euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); + } + + /* swap values for next iteration, check for fatal inputs */ + if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { + /* Do something */ + } else { + /* due to inputs or numerical failure the output is invalid, skip it */ + continue; + } + + if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator so3_comp] sensor data missed! (%llu)\n", raw.timestamp - last_data); + + last_data = raw.timestamp; + + /* send out */ + att.timestamp = raw.timestamp; + + // XXX Apply the same transformation to the rotation matrix + att.roll = euler[0] - so3_comp_params.roll_off; + att.pitch = euler[1] - so3_comp_params.pitch_off; + att.yaw = euler[2] - so3_comp_params.yaw_off; + + /* FIXME : This can be a problem for rate controller. Rate in body or inertial? + att.rollspeed = x_aposteriori[0]; + att.pitchspeed = x_aposteriori[1]; + att.yawspeed = x_aposteriori[2]; + att.rollacc = x_aposteriori[3]; + att.pitchacc = x_aposteriori[4]; + att.yawacc = x_aposteriori[5]; + */ + + //att.yawspeed =z_k[2] ; + /* copy offsets */ + //memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets)); + + /* copy rotation matrix */ + memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix)); + att.R_valid = true; + + if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) { + // Broadcast + orb_publish(ORB_ID(vehicle_attitude), pub_att, &att); + + } else { + warnx("NaN in roll/pitch/yaw estimate!"); + } + + perf_end(so3_comp_loop_perf); + } + } + } + + loopcounter++; + } + + thread_running = false; + + return 0; +} diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c new file mode 100755 index 0000000000..bf0f49db84 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -0,0 +1,44 @@ +/* + * @file attitude_estimator_so3_comp_params.c + * + * Parameters for SO3 complementary filter + */ + +#include "attitude_estimator_so3_comp_params.h" + +/* This is filter gain for nonlinear SO3 complementary filter */ +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); +PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); + +/* offsets in roll, pitch and yaw of sensor plane and body */ +PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); +PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f); +PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f); + +int parameters_init(struct attitude_estimator_ekf_param_handles *h) +{ + /* Filter gain parameters */ + h->Kp = param_find("SO3_COMP_KP"); + h->Ki = param_find("SO3_COMP_KI"); + + /* Attitude offset (WARNING: Do not change if you do not know what exactly this variable wil lchange) */ + h->roll_off = param_find("ATT_ROLL_OFFS"); + h->pitch_off = param_find("ATT_PITCH_OFFS"); + h->yaw_off = param_find("ATT_YAW_OFFS"); + + return OK; +} + +int parameters_update(const struct attitude_estimator_ekf_param_handles *h, struct attitude_estimator_ekf_params *p) +{ + /* Update filter gain */ + param_get(h->Kp, &(p->Kp)); + param_get(h->Ki, &(p->Ki)); + + /* Update attitude offset */ + param_get(h->roll_off, &(p->roll_off)); + param_get(h->pitch_off, &(p->pitch_off)); + param_get(h->yaw_off, &(p->yaw_off)); + + return OK; +} diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h new file mode 100755 index 0000000000..2fccec61ce --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h @@ -0,0 +1,32 @@ +/* + * @file attitude_estimator_so3_comp_params.h + * + * Parameters for EKF filter + */ + +#include + +struct attitude_estimator_so3_comp_params { + float Kp; + float Ki; + float roll_off; + float pitch_off; + float yaw_off; +}; + +struct attitude_estimator_so3_comp_param_handles { + param_t Kp, Ki; + param_t roll_off, pitch_off, yaw_off; +}; + +/** + * Initialize all parameter handles and values + * + */ +int parameters_init(struct attitude_estimator_so3_comp_param_handles *h); + +/** + * Update all parameters + * + */ +int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p); diff --git a/src/modules/attitude_estimator_so3_comp/module.mk b/src/modules/attitude_estimator_so3_comp/module.mk new file mode 100644 index 0000000000..92f43d9202 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/module.mk @@ -0,0 +1,8 @@ +# +# Attitude estimator (Nonlinear SO3 complementary Filter) +# + +MODULE_COMMAND = attitude_estimator_so3_comp + +SRCS = attitude_estimator_so3_comp_main.cpp \ + attitude_estimator_so3_comp_params.c From cd7b0f7aab39099353bda46ba9a498c242d75791 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 16:12:19 +1000 Subject: [PATCH 16/89] I missed to add build command --- makefiles/config_px4fmu_default.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 1e4d592665..4cf650a986 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -61,6 +61,7 @@ MODULES += modules/mavlink_onboard # Estimation modules (EKF / other filters) # MODULES += modules/attitude_estimator_ekf +MODULES += modules/attitude_estimator_so3_comp MODULES += modules/position_estimator_mc MODULES += modules/position_estimator MODULES += modules/att_pos_estimator_ekf From 0c3412223b0961798e0fa9c27042132ebdfc0bdb Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 16:17:20 +1000 Subject: [PATCH 17/89] Fixed few minor bug --- .../attitude_estimator_so3_comp_main.cpp | 6 ++++++ .../attitude_estimator_so3_comp_params.c | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 381b0df75c..81a5e5b07f 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -44,6 +45,7 @@ static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame +volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki /** * Mainloop of attitude_estimator_so3_comp. @@ -525,6 +527,10 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float bSq = q1*q1; float cSq = q2*q2; float dSq = q3*q3; + float a = q0; + float b = q1; + float c = q2; + float d = q3; Rot_matrix[0] = aSq + bSq - cSq - dSq; Rot_matrix[1] = 2.0 * (b * c - a * d); diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index bf0f49db84..158eb19725 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -15,7 +15,7 @@ PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f); PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f); -int parameters_init(struct attitude_estimator_ekf_param_handles *h) +int parameters_init(struct attitude_estimator_so3_comp_param_handles *h) { /* Filter gain parameters */ h->Kp = param_find("SO3_COMP_KP"); @@ -29,7 +29,7 @@ int parameters_init(struct attitude_estimator_ekf_param_handles *h) return OK; } -int parameters_update(const struct attitude_estimator_ekf_param_handles *h, struct attitude_estimator_ekf_params *p) +int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p) { /* Update filter gain */ param_get(h->Kp, &(p->Kp)); From 32bace0824ca37c424cc98ecca6ced86cfe10149 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 17:52:12 +1000 Subject: [PATCH 18/89] I do not know why roll angle is not correct. But system looks okay --- .../attitude_estimator_so3_comp_main.cpp | 72 ++++++++++--------- 1 file changed, 38 insertions(+), 34 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 81a5e5b07f..a8561a0780 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -44,8 +44,8 @@ extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]) static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ -volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame -volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame +static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki /** * Mainloop of attitude_estimator_so3_comp. @@ -135,7 +135,6 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float float recipNorm; float halfvx, halfvy, halfvz; float halfex, halfey, halfez; - float qa, qb, qc; // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { @@ -181,13 +180,10 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); + q0 += (-q1 * gx - q2 * gy - q3 * gz); + q1 += (q0 * gx + q2 * gz - q3 * gy); + q2 += (q0 * gy - q1 * gz + q3 * gx); + q3 += (q0 * gz + q1 * gy - q2 * gx); // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -203,7 +199,6 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az float hx, hy, bx, bz; float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; float halfex, halfey, halfez; - float qa, qb, qc; // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { @@ -282,13 +277,10 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); + q0 += (-q1 * gx - q2 * gy - q3 * gz); + q1 += (q0 * gx + q2 * gz - q3 * gy); + q2 += (q0 * gy - q1 * gz + q3 * gx); + q3 += (q0 * gz + q1 * gy - q2 * gx); // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -532,19 +524,19 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float c = q2; float d = q3; - Rot_matrix[0] = aSq + bSq - cSq - dSq; - Rot_matrix[1] = 2.0 * (b * c - a * d); - Rot_matrix[2] = 2.0 * (a * c + b * d); - Rot_matrix[3] = 2.0 * (b * c + a * d); - Rot_matrix[4] = aSq - bSq + cSq - dSq; - Rot_matrix[5] = 2.0 * (c * d - a * b); - Rot_matrix[6] = 2.0 * (b * d - a * c); - Rot_matrix[7] = 2.0 * (a * b + c * d); - Rot_matrix[8] = aSq - bSq - cSq + dSq; + Rot_matrix[0] = aSq + bSq - cSq - dSq; // 11 + Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 + Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 + Rot_matrix[3] = 2.0 * (b * c + a * d); // 21 + Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 + Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 + Rot_matrix[6] = 2.0 * (b * d - a * c); // 31 + Rot_matrix[7] = 2.0 * (a * b + c * d); // 32 + Rot_matrix[8] = aSq - bSq - cSq + dSq; // 33 - /* Compute Euler angle */ - float theta = asinf(-Rot_matrix[6]); - euler[1] = theta; + /* FIXME : Work around this later... + float theta = asinf(-Rot_matrix[6]); // -r_{31} + euler[1] = theta; // pitch angle if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ euler[0] = 0.0f; @@ -556,6 +548,16 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); } + */ + + float q1q1 = q1*q1; + float q2q2 = q2*q2; + float q3q3 = q3*q3; + + euler[0] = atan2f(2*(q0*q1 + q2*q3),1-2*(q1q1+q2q2)); // roll + euler[1] = asinf(2*(q0*q2 - q3*q1)); // pitch + euler[2] = atan2f(2*(q0*q3 + q1*q2),1-2*(q2q2 + q3q3)); // yaw + /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { @@ -577,10 +579,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.pitch = euler[1] - so3_comp_params.pitch_off; att.yaw = euler[2] - so3_comp_params.yaw_off; - /* FIXME : This can be a problem for rate controller. Rate in body or inertial? - att.rollspeed = x_aposteriori[0]; - att.pitchspeed = x_aposteriori[1]; - att.yawspeed = x_aposteriori[2]; + /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ + att.rollspeed = q1; + att.pitchspeed = q2; + att.yawspeed = q3; + + /* att.rollacc = x_aposteriori[3]; att.pitchacc = x_aposteriori[4]; att.yawacc = x_aposteriori[5]; From f547044203f81061a9302f1e5c4fcdf2ef73cac2 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 22 May 2013 00:09:25 +1000 Subject: [PATCH 19/89] Roll pitch yaw should be verified again --- .../attitude_estimator_so3_comp_main.cpp | 180 +++++++++--------- .../attitude_estimator_so3_comp_params.c | 2 +- 2 files changed, 91 insertions(+), 91 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index a8561a0780..ff63640ef9 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -139,52 +139,52 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; - // Estimated direction of gravity and vector perpendicular to magnetic flux - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; + // Estimated direction of gravity and vector perpendicular to magnetic flux + halfvx = q1 * q3 - q0 * q2; + halfvy = q0 * q1 + q2 * q3; + halfvz = q0 * q0 - 0.5f + q3 * q3; - // Error is sum of cross product between estimated and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); + // Error is sum of cross product between estimated and measured direction of gravity + halfex = (ay * halfvz - az * halfvy); + halfey = (az * halfvx - ax * halfvz); + halfez = (ax * halfvy - ay * halfvx); - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 += (-q1 * gx - q2 * gy - q3 * gz); + q0 +=(-q1 * gx - q2 * gy - q3 * gz); q1 += (q0 * gx + q2 * gz - q3 * gy); q2 += (q0 * gy - q1 * gz + q3 * gx); q3 += (q0 * gz + q1 * gy - q2 * gx); - + // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); q0 *= recipNorm; @@ -209,17 +209,17 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; // Auxiliary variables to avoid repeated arithmetic q0q0 = q0 * q0; @@ -239,45 +239,45 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az bx = sqrt(hx * hx + hy * hy); bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - // Error is sum of cross product between estimated direction and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); + halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); + halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 += (-q1 * gx - q2 * gy - q3 * gz); + q0 +=(-q1 * gx - q2 * gy - q3 * gz); q1 += (q0 * gx + q2 * gz - q3 * gy); q2 += (q0 * gy - q1 * gz + q3 * gx); q3 += (q0 * gz + q1 * gy - q2 * gx); @@ -515,24 +515,28 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); - float aSq = q0*q0; - float bSq = q1*q1; - float cSq = q2*q2; - float dSq = q3*q3; + float aSq = q0*q0; // 1 + float bSq = q1*q1; // 2 + float cSq = q2*q2; // 3 + float dSq = q3*q3; // 4 float a = q0; float b = q1; float c = q2; float d = q3; - Rot_matrix[0] = aSq + bSq - cSq - dSq; // 11 - Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 - Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 - Rot_matrix[3] = 2.0 * (b * c + a * d); // 21 - Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 - Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 - Rot_matrix[6] = 2.0 * (b * d - a * c); // 31 - Rot_matrix[7] = 2.0 * (a * b + c * d); // 32 - Rot_matrix[8] = aSq - bSq - cSq + dSq; // 33 + Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11 + //Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 + //Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 + Rot_matrix[3] = 2.0 * (b * c - a * d); // 21 + //Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 + //Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 + Rot_matrix[6] = 2.0 * (b * d + a * c); // 31 + Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 + Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 + + //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); + //euler[1] = asinf(-Rot_matrix[6]); + //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); /* FIXME : Work around this later... float theta = asinf(-Rot_matrix[6]); // -r_{31} @@ -550,13 +554,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } */ - float q1q1 = q1*q1; - float q2q2 = q2*q2; - float q3q3 = q3*q3; - - euler[0] = atan2f(2*(q0*q1 + q2*q3),1-2*(q1q1+q2q2)); // roll - euler[1] = asinf(2*(q0*q2 - q3*q1)); // pitch - euler[2] = atan2f(2*(q0*q3 + q1*q2),1-2*(q2q2 + q3q3)); // yaw + euler[0] = atan2f(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); + euler[1] = asinf(2*(q0*q2-q3*q1)); + euler[2] = atan2f(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); /* swap values for next iteration, check for fatal inputs */ diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 158eb19725..068e4340a6 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -7,7 +7,7 @@ #include "attitude_estimator_so3_comp_params.h" /* This is filter gain for nonlinear SO3 complementary filter */ -PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 0.5f); PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); /* offsets in roll, pitch and yaw of sensor plane and body */ From 364d1a06e308334915c5e7e54e1c6f15b11e5b2e Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 22 May 2013 13:03:14 +1000 Subject: [PATCH 20/89] To use freeIMU processing visualization tool, I have implemented float number transmission over uart (default /dev/ttyS2, 115200) But this not tested yet. I should. --- .../attitude_estimator_so3_comp_main.cpp | 271 +++++++++++++----- 1 file changed, 195 insertions(+), 76 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index ff63640ef9..ac898eefc1 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -47,6 +47,10 @@ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thr static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +//! Serial packet related +static int uart; +static int baudrate; + /** * Mainloop of attitude_estimator_so3_comp. */ @@ -63,7 +67,9 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-p ]\n\n"); + fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-d ] [-b ]\n" + "-d and -b options are for separate visualization with raw data (quaternion packet) transfer\n" + "ex) attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200\n"); exit(1); } @@ -80,6 +86,8 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) if (argc < 1) usage("missing command"); + + if (!strcmp(argv[1], "start")) { if (thread_running) { @@ -94,12 +102,18 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) SCHED_PRIORITY_MAX - 5, 12400, attitude_estimator_so3_comp_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); + (const char **)argv); exit(0); } if (!strcmp(argv[1], "stop")) { thread_should_exit = true; + + while(thread_running){ + usleep(200000); + printf("."); + } + printf("terminated."); exit(0); } @@ -121,76 +135,18 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) //--------------------------------------------------------------------------------------------------- // Fast inverse square-root // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root -float invSqrt(float x) { - float halfx = 0.5f * x; - float y = x; - long i = *(long*)&y; - i = 0x5f3759df - (i>>1); - y = *(float*)&i; - y = y * (1.5f - (halfx * y * y)); - return y; -} +float invSqrt(float number) { + volatile long i; + volatile float x, y; + volatile const float f = 1.5F; -void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az, float twoKp, float twoKi, float dt) { - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity and vector perpendicular to magnetic flux - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - // Error is sum of cross product between estimated and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * dt); // pre-multiply common factors - gy *= (0.5f * dt); - gz *= (0.5f * dt); - q0 +=(-q1 * gx - q2 * gy - q3 * gz); - q1 += (q0 * gx + q2 * gz - q3 * gy); - q2 += (q0 * gy - q1 * gz + q3 * gx); - q3 += (q0 * gz + q1 * gy - q2 * gx); - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; + x = number * 0.5F; + y = number; + i = * (( long * ) &y); + i = 0x5f375a86 - ( i >> 1 ); + y = * (( float * ) &i); + y = y * ( f - ( x * y * y ) ); + return y; } void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { @@ -202,7 +158,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); + //MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); return; } @@ -290,6 +246,117 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az q3 *= recipNorm; } +void send_uart_byte(char c) +{ + write(uart,&c,1); +} + +void send_uart_bytes(uint8_t *data, int length) +{ + write(uart,data,(size_t)(sizeof(uint8_t)*length)); +} + +void send_uart_float(float f) { + uint8_t * b = (uint8_t *) &f; + + //! Assume float is 4-bytes + for(int i=0; i<4; i++) { + + uint8_t b1 = (b[i] >> 4) & 0x0f; + uint8_t b2 = (b[i] & 0x0f); + + uint8_t c1 = (b1 < 10) ? ('0' + b1) : 'A' + b1 - 10; + uint8_t c2 = (b2 < 10) ? ('0' + b2) : 'A' + b2 - 10; + + send_uart_bytes(&c1,1); + send_uart_bytes(&c2,1); + } +} + +void send_uart_float_arr(float *arr, int length) +{ + for(int i=0;i, default : /dev/ttyS2 + //! -b , default : 115200 + while ((ch = getopt(argc,argv,"d:b:")) != EOF){ + switch(ch){ + case 'b': + baudrate = strtoul(optarg, NULL, 10); + if(baudrate == 0) + printf("invalid baud rate '%s'",optarg); + break; + case 'd': + device_name = optarg; + debug_mode = true; + break; + default: + usage("invalid argument"); + } + } + + if(debug_mode){ + uart = open_uart(baudrate, device_name, &uart_config_original, &usb_uart); + if (uart < 0) + printf("could not open %s", device_name); + } + // print text printf("Nonlinear SO3 Attitude Estimator initialized..\n\n"); fflush(stdout); @@ -554,9 +658,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } */ - euler[0] = atan2f(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - euler[1] = asinf(2*(q0*q2-q3*q1)); - euler[2] = atan2f(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); + euler[2] = atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); + euler[1]= -asinf(2*(q1*q3+q0*q2)); + euler[0] = atan2f(2*(q2*q3-q0*q1),2*(q0*q0+q3*q3)-1); /* swap values for next iteration, check for fatal inputs */ @@ -607,7 +711,18 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } perf_end(so3_comp_loop_perf); - } + + if(debug_mode) + { + float quat[4]; + quat[0] = q0; + quat[1] = q1; + quat[2] = q2; + quat[3] = q3; + send_uart_float_arr(quat,4); + send_uart_byte('\n'); + } + }// else } } @@ -616,5 +731,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds thread_running = false; + /* Reset the UART flags to original state */ + if (!usb_uart) + tcsetattr(uart, TCSANOW, &uart_config_original); + return 0; } From 4bf05054218efab3b3dc182939f32a96f5ed1673 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Thu, 23 May 2013 16:12:29 +1000 Subject: [PATCH 21/89] Test flight has been performed with nonlinear SO(3) attitude estimator. Here are few observations: - When the system initialized, roll angle is initially reversed. As filter converged, it becomes normal. - I put a negative sign on roll, yaw. It should naturally has right sign, but I do not know why for now. Let me investigate again. - Gain : I do not know what gain is good for quadrotor flight. Let me take a look Ardupilot gain in the later. Anyway, you can fly with this attitude estimator. --- nuttx/configs/px4fmu/nsh/defconfig | 6 +- .../attitude_estimator_so3_comp_main.cpp | 220 +++++++++--------- 2 files changed, 114 insertions(+), 112 deletions(-) diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 02e2243020..94d99112e2 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_SERIAL_CONSOLE=n CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y +CONFIG_DEV_CONSOLE=n CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=n +CONFIG_CDCACM_CONSOLE=y #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index ac898eefc1..28fcf03692 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -44,8 +44,9 @@ extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]) static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ -static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame -static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ +static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ +static float gravity_vector[3] = {0.0f,0.0f,0.0f}; /** estimated gravity vector */ //! Serial packet related static int uart; @@ -151,82 +152,91 @@ float invSqrt(float number) { void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; + float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; - // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) + //! If magnetometer measurement is available, use it. if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - //MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); - return; + float hx, hy, bx, bz; + float halfwx, halfwy, halfwz; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Reference direction of Earth's magnetic field + hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); + hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + bx = sqrt(hx * hx + hy * hy); + bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + + // Estimated direction of magnetic field + halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); + halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); + halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex += (my * halfwz - mz * halfwy); + halfey += (mz * halfwx - mx * halfwz); + halfez += (mx * halfwy - my * halfwx); } // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + float halfvx, halfvy, halfvz; - // Error is sum of cross product between estimated direction and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex += ay * halfvz - az * halfvy; + halfey += az * halfvx - ax * halfvz; + halfez += ax * halfvy - ay * halfvx; } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply feedback only when valid data has been gathered from the accelerometer or magnetometer + if(halfex != 0.0f && halfey != 0.0f && halfez != 0.0f) { + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + gyro_bias[0] += twoKi * halfex * dt; // integral error scaled by Ki + gyro_bias[1] += twoKi * halfey * dt; + gyro_bias[2] += twoKi * halfez * dt; + gx += gyro_bias[0]; // apply integral feedback + gy += gyro_bias[1]; + gz += gyro_bias[2]; + } + else { + gyro_bias[0] = 0.0f; // prevent integral windup + gyro_bias[1] = 0.0f; + gyro_bias[2] = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion @@ -309,11 +319,11 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi case 460800: speed = B460800; break; case 921600: speed = B921600; break; default: - fprintf(stderr, "ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); + printf("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); return -EINVAL; } - printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud); + printf("[so3_comp_filt] UART is %s, baudrate is %d\n", uart_name, baud); uart = open(uart_name, O_RDWR | O_NOCTTY); /* Try to set baud rate */ @@ -321,11 +331,11 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi int termios_state; *is_usb = false; - /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ + /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) { /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - fprintf(stderr, "ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); + printf("ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); close(uart); return -1; } @@ -338,14 +348,14 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - fprintf(stderr, "ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); + printf("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); close(uart); return -1; } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - fprintf(stderr, "ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); + printf("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); close(uart); return -1; } @@ -420,9 +430,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } if(debug_mode){ + printf("Opening debugging port for 3D visualization\n"); uart = open_uart(baudrate, device_name, &uart_config_original, &usb_uart); if (uart < 0) printf("could not open %s", device_name); + else + printf("Open port success\n"); } // print text @@ -638,30 +651,22 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 + gravity_vector[0] = 2*(q1*q3-q0*q2); + gravity_vector[1] = 2*(q0*q1+q2*q3); + gravity_vector[2] = aSq - bSq - cSq + dSq; + //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - //euler[1] = asinf(-Rot_matrix[6]); + //euler[1] = -asinf(Rot_matrix[6]); //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); - /* FIXME : Work around this later... - float theta = asinf(-Rot_matrix[6]); // -r_{31} - euler[1] = theta; // pitch angle - - if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ - euler[0] = 0.0f; - euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); - } else if (fabsf(theta + M_PI_2_F) < 1.0e-3f) { - euler[0] = 0.0f; - euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); - } else { - euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); - } - */ - - euler[2] = atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); - euler[1]= -asinf(2*(q1*q3+q0*q2)); - euler[0] = atan2f(2*(q2*q3-q0*q1),2*(q0*q0+q3*q3)-1); - + // Euler angle directly from quaternion. + euler[0] = -atan2f(gravity_vector[1], sqrtf(gravity_vector[0]*gravity_vector[0] + gravity_vector[2]*gravity_vector[2])); // roll + euler[1] = atan2f(gravity_vector[0], sqrtf(gravity_vector[1]*gravity_vector[1] + gravity_vector[2]*gravity_vector[2])); // pitch + euler[2] = -atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); // yaw + + //euler[2] = atan2(2 * q1*q2 - 2 * q0*q3, 2 * q0*q0 + 2 * q1*q1 - 1); // psi + //euler[1] = -asin(2 * q1*q3 + 2 * q0*q2); // theta + //euler[0] = atan2(2 * q2*q3 - 2 * q0*q1, 2 * q0*q0 + 2 * q3*q3 - 1); // phi /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { @@ -684,19 +689,15 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.yaw = euler[2] - so3_comp_params.yaw_off; /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ - att.rollspeed = q1; - att.pitchspeed = q2; - att.yawspeed = q3; + att.rollspeed = gyro[0]; + att.pitchspeed = gyro[1]; + att.yawspeed = gyro[2]; + att.rollacc = 0; + att.pitchacc = 0; + att.yawacc = 0; - /* - att.rollacc = x_aposteriori[3]; - att.pitchacc = x_aposteriori[4]; - att.yawacc = x_aposteriori[5]; - */ - - //att.yawspeed =z_k[2] ; - /* copy offsets */ - //memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets)); + /* TODO: Bias estimation required */ + memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets)); /* copy rotation matrix */ memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix)); @@ -712,6 +713,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds perf_end(so3_comp_loop_perf); + //! This will print out debug packet to visualization software if(debug_mode) { float quat[4]; @@ -722,12 +724,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds send_uart_float_arr(quat,4); send_uart_byte('\n'); } - }// else + } } } loopcounter++; - } + }// while thread_running = false; From 81acd98997ff3d605c8c797f04e81e64db180a57 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 23 May 2013 08:54:08 +0200 Subject: [PATCH 22/89] Added limit to heading command --- src/examples/fixedwing_control/main.c | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 1753070e2f..6a9ad9e1d1 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -154,7 +154,14 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct v /* calculate heading error */ float yaw_err = att->yaw - bearing; /* apply control gain */ - att_sp->roll_body = yaw_err * p.hdng_p; + float roll_command = yaw_err * p.hdng_p; + + /* limit output, this commonly is a tuning parameter, too */ + if (att_sp->roll_body < -0.5f) { + att_sp->roll_body = -0.5f; + } else if (att_sp->roll_body > 0.5f) { + att_sp->roll_body = 0.5f; + } } /* Main Thread */ From dca844a808643131ee299a46a7cb82aea933822f Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 23 May 2013 00:40:22 +0200 Subject: [PATCH 23/89] Based on comments in: MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit http://answers.px4.ethz.ch/question/1337/px4io-receiver-connection-problem/?answer=1346#post-id-1346 increase the longest PPM pulse we recognize out to 550µs. --- src/drivers/stm32/drv_hrt.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index cec0c49ffd..fd63681e30 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -330,7 +330,7 @@ static void hrt_call_invoke(void); /* * PPM decoder tuning parameters */ -# define PPM_MAX_PULSE_WIDTH 500 /* maximum width of a pulse */ +# define PPM_MAX_PULSE_WIDTH 550 /* maximum width of a valid pulse */ # define PPM_MIN_CHANNEL_VALUE 800 /* shortest valid channel signal */ # define PPM_MAX_CHANNEL_VALUE 2200 /* longest valid channel signal */ # define PPM_MIN_START 2500 /* shortest valid start gap */ From 9f090e651a2f9bc7c3c63022a6ff26453b465b67 Mon Sep 17 00:00:00 2001 From: marco Date: Thu, 23 May 2013 21:03:49 +0200 Subject: [PATCH 24/89] mkblctrl cleanup --- src/drivers/mkblctrl/mkblctrl.cpp | 519 ++++++++++++++++-------------- 1 file changed, 278 insertions(+), 241 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index 3a735e26fb..f6e4e0ed3e 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -76,7 +76,6 @@ #include #include -#include #define I2C_BUS_SPEED 400000 #define UPDATE_RATE 400 @@ -114,6 +113,7 @@ public: virtual int ioctl(file *filp, int cmd, unsigned long arg); virtual int init(unsigned motors); + virtual ssize_t write(file *filp, const char *buffer, size_t len); int set_mode(Mode mode); int set_pwm_rate(unsigned rate); @@ -177,9 +177,10 @@ private: int gpio_ioctl(file *filp, int cmd, unsigned long arg); int mk_servo_arm(bool status); - int mk_servo_set(unsigned int chan, float val); - int mk_servo_set_test(unsigned int chan, float val); + int mk_servo_set(unsigned int chan, short val); + int mk_servo_set_value(unsigned int chan, short val); int mk_servo_test(unsigned int chan); + short scaling(float val, float inMin, float inMax, float outMin, float outMax); }; @@ -207,20 +208,20 @@ const int blctrlAddr_octo_x[] = { 1, 4, 0, 1, -4, 1, 1, -4 }; // Addresstranslat const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0}; -int addrTranslator[] = {0,0,0,0,0,0,0,0}; +int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0}; -struct MotorData_t -{ +struct MotorData_t { unsigned int Version; // the version of the BL (0 = old) - unsigned int SetPoint; // written by attitude controller - unsigned int SetPointLowerBits; // for higher Resolution of new BLs - unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present - unsigned int ReadMode; // select data to read - // the following bytes must be exactly in that order! - unsigned int Current; // in 0.1 A steps, read back from BL - unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit - unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in - unsigned int RoundCount; + unsigned int SetPoint; // written by attitude controller + unsigned int SetPointLowerBits; // for higher Resolution of new BLs + unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present + unsigned int ReadMode; // select data to read + unsigned short RawPwmValue; // length of PWM pulse + // the following bytes must be exactly in that order! + unsigned int Current; // in 0.1 A steps, read back from BL + unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit + unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in + unsigned int RoundCount; }; MotorData_t Motor[MAX_MOTORS]; @@ -314,7 +315,7 @@ MK::init(unsigned motors) /* start the IO interface task */ _task = task_spawn("mkblctrl", SCHED_DEFAULT, - SCHED_PRIORITY_MAX -20, + SCHED_PRIORITY_MAX - 20, 2048, (main_t)&MK::task_main_trampoline, nullptr); @@ -346,27 +347,11 @@ MK::set_mode(Mode mode) */ switch (mode) { case MODE_2PWM: - if(_num_outputs == 4) { - //debug("MODE_QUAD"); - } else if(_num_outputs == 6) { - //debug("MODE_HEXA"); - } else if(_num_outputs == 8) { - //debug("MODE_OCTO"); - } - //up_pwm_servo_init(0x3); up_pwm_servo_deinit(); _update_rate = UPDATE_RATE; /* default output rate */ break; case MODE_4PWM: - if(_num_outputs == 4) { - //debug("MODE_QUADRO"); - } else if(_num_outputs == 6) { - //debug("MODE_HEXA"); - } else if(_num_outputs == 8) { - //debug("MODE_OCTO"); - } - //up_pwm_servo_init(0xf); up_pwm_servo_deinit(); _update_rate = UPDATE_RATE; /* default output rate */ break; @@ -412,45 +397,55 @@ MK::set_frametype(int frametype) int MK::set_motor_count(unsigned count) { - if(count > 0) { + if (count > 0) { _num_outputs = count; - if(_px4mode == MAPPING_MK) { - if(_frametype == FRAME_PLUS) { + if (_px4mode == MAPPING_MK) { + if (_frametype == FRAME_PLUS) { fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); - } else if(_frametype == FRAME_X) { + + } else if (_frametype == FRAME_X) { fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); } - if(_num_outputs == 4) { - if(_frametype == FRAME_PLUS) { + + if (_num_outputs == 4) { + if (_frametype == FRAME_PLUS) { memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); - } else if(_frametype == FRAME_X) { + + } else if (_frametype == FRAME_X) { memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); } - } else if(_num_outputs == 6) { - if(_frametype == FRAME_PLUS) { + + } else if (_num_outputs == 6) { + if (_frametype == FRAME_PLUS) { memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); - } else if(_frametype == FRAME_X) { + + } else if (_frametype == FRAME_X) { memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); } - } else if(_num_outputs == 8) { - if(_frametype == FRAME_PLUS) { + + } else if (_num_outputs == 8) { + if (_frametype == FRAME_PLUS) { memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); - } else if(_frametype == FRAME_X) { + + } else if (_frametype == FRAME_X) { memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); } } + } else { fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); } - if(_num_outputs == 4) { + if (_num_outputs == 4) { fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); - } else if(_num_outputs == 6) { + + } else if (_num_outputs == 6) { fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); - } else if(_num_outputs == 8) { + + } else if (_num_outputs == 8) { fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); } @@ -469,16 +464,35 @@ MK::set_motor_test(bool motortest) return OK; } +short +MK::scaling(float val, float inMin, float inMax, float outMin, float outMax) +{ + short retVal = 0; + + retVal = (val - inMin) / (inMax - inMin) * (outMax - outMin) + outMin; + + if (retVal < outMin) { + retVal = outMin; + + } else if (retVal > outMax) { + retVal = outMax; + } + + return retVal; +} void MK::task_main() { + long update_rate_in_us = 0; + float tmpVal = 0; + /* * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. */ _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : - ORB_ID(actuator_controls_1)); + ORB_ID(actuator_controls_0)); /* force a reset of the update rate */ _current_update_rate = 0; @@ -488,16 +502,11 @@ MK::task_main() /* advertise the mixed control outputs */ actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); - /* advertise the mixed control outputs */ - _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), - &outputs); /* advertise the effective control inputs */ actuator_controls_effective_s controls_effective; memset(&controls_effective, 0, sizeof(controls_effective)); /* advertise the effective control inputs */ - _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), - &controls_effective); pollfd fds[2]; fds[0].fd = _t_actuators; @@ -505,15 +514,7 @@ MK::task_main() fds[1].fd = _t_armed; fds[1].events = POLLIN; - // rc input, published to ORB - struct rc_input_values rc_in; - orb_advert_t to_input_rc = 0; - - memset(&rc_in, 0, sizeof(rc_in)); - rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; - log("starting"); - long update_rate_in_us = 0; /* loop until killed */ while (!_task_should_exit) { @@ -528,6 +529,7 @@ MK::task_main() update_rate_in_ms = 2; _update_rate = 500; } + /* reject slower than 50 Hz updates */ if (update_rate_in_ms > 20) { update_rate_in_ms = 20; @@ -539,8 +541,9 @@ MK::task_main() _current_update_rate = _update_rate; } - /* sleep waiting for data, but no more than a second */ - int ret = ::poll(&fds[0], 2, 1000); + /* sleep waiting for data, stopping to check for PPM + * input at 100Hz */ + int ret = ::poll(&fds[0], 2, 100); /* this would be bad... */ if (ret < 0) { @@ -553,7 +556,7 @@ MK::task_main() if (fds[0].revents & POLLIN) { /* get controls - must always do this to avoid spinning */ - orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls); + orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_0), _t_actuators, &_controls); /* can we mix? */ if (_mixers != nullptr) { @@ -565,53 +568,52 @@ MK::task_main() // XXX output actual limited values memcpy(&controls_effective, &_controls, sizeof(controls_effective)); - orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective); - /* iterate actuators */ for (unsigned int i = 0; i < _num_outputs; i++) { /* last resort: catch NaN, INF and out-of-band errors */ if (i < outputs.noutputs && - isfinite(outputs.output[i]) && - outputs.output[i] >= -1.0f && - outputs.output[i] <= 1.0f) { + isfinite(outputs.output[i]) && + outputs.output[i] >= -1.0f && + outputs.output[i] <= 1.0f) { /* scale for PWM output 900 - 2100us */ - //outputs.output[i] = 1500 + (600 * outputs.output[i]); - //outputs.output[i] = 127 + (127 * outputs.output[i]); + /* nothing to do here */ } else { /* * Value is NaN, INF or out of band - set to the minimum value. * This will be clearly visible on the servo status and will limit the risk of accidentally * spinning motors. It would be deadly in flight. */ - if(outputs.output[i] < -1.0f) { + if (outputs.output[i] < -1.0f) { outputs.output[i] = -1.0f; - } else if(outputs.output[i] > 1.0f) { + + } else if (outputs.output[i] > 1.0f) { outputs.output[i] = 1.0f; + } else { outputs.output[i] = -1.0f; } } /* don't go under BLCTRL_MIN_VALUE */ - if(outputs.output[i] < BLCTRL_MIN_VALUE) { + if (outputs.output[i] < BLCTRL_MIN_VALUE) { outputs.output[i] = BLCTRL_MIN_VALUE; } - //_motortest = true; - /* output to BLCtrl's */ - if(_motortest == true) { - mk_servo_test(i); - } else { - //mk_servo_set(i, outputs.output[i]); - mk_servo_set_test(i, outputs.output[i]); // 8Bit - } + /* output to BLCtrl's */ + if (_motortest == true) { + mk_servo_test(i); + + } else { + mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine + } } - /* and publish for anyone that cares to see */ - orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs); } + + + } /* how about an arming update? */ @@ -622,29 +624,9 @@ MK::task_main() orb_copy(ORB_ID(actuator_armed), _t_armed, &aa); /* update PWM servo armed status if armed and not locked down */ - ////up_pwm_servo_arm(aa.armed && !aa.lockdown); mk_servo_arm(aa.armed && !aa.lockdown); } - // see if we have new PPM input data - if (ppm_last_valid_decode != rc_in.timestamp) { - // we have a new PPM frame. Publish it. - rc_in.channel_count = ppm_decoded_channels; - if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) { - rc_in.channel_count = RC_INPUT_MAX_CHANNELS; - } - for (uint8_t i=0; i 2047) { - tmpVal = 2047; + if (tmpVal > 1024) { + tmpVal = 1024; + + } else if (tmpVal < 0) { + tmpVal = 0; } + Motor[chan].SetPoint = (uint8_t)(tmpVal / 4); + //Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 4; - Motor[chan].SetPoint = (uint8_t) tmpVal / 3; // divide 8 - Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 8; // rest of divide 8 - //rod = (uint8_t) tmpVal % 8; - //Motor[chan].SetPointLowerBits = rod<<1; // rest of divide 8 Motor[chan].SetPointLowerBits = 0; - if(_armed == false) { + if (_armed == false) { Motor[chan].SetPoint = 0; Motor[chan].SetPointLowerBits = 0; } //if(Motor[chan].State & MOTOR_STATE_PRESENT_MASK) { - set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + + if (Motor[chan].Version == BLCTRL_OLD) { + /* + * Old BL-Ctrl 8Bit served. Version < 2.0 + */ + msg[0] = Motor[chan].SetPoint; + + if (Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], 1, &result[0], 2)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = 255;; - if(Motor[chan].Version == BLCTRL_OLD) { - /* - * Old BL-Ctrl 8Bit served. Version < 2.0 - */ - msg[0] = Motor[chan].SetPoint; - if(Motor[chan].RoundCount >= 16) { - // on each 16th cyle we read out the status messages from the blctrl - if (OK == transfer(&msg[0], 1, &result[0], 2)) { - Motor[chan].Current = result[0]; - Motor[chan].MaxPWM = result[1]; - Motor[chan].Temperature = 255;; - } else { - if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error - } - Motor[chan].RoundCount = 0; } else { - if (OK != transfer(&msg[0], 1, nullptr, 0)) { - if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error - } + if ((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error } + Motor[chan].RoundCount = 0; + } else { - /* - * New BL-Ctrl 11Bit served. Version >= 2.0 - */ - msg[0] = Motor[chan].SetPoint; - msg[1] = Motor[chan].SetPointLowerBits; - - if(Motor[chan].SetPointLowerBits == 0) { - bytesToSendBL2 = 1; // if setpoint lower bits are zero, we send only the higher bits - this saves time + if (OK != transfer(&msg[0], 1, nullptr, 0)) { + if ((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error } - - if(Motor[chan].RoundCount >= 16) { - // on each 16th cyle we read out the status messages from the blctrl - if (OK == transfer(&msg[0], bytesToSendBL2, &result[0], 3)) { - Motor[chan].Current = result[0]; - Motor[chan].MaxPWM = result[1]; - Motor[chan].Temperature = result[2]; - } else { - if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error - } - Motor[chan].RoundCount = 0; - } else { - if (OK != transfer(&msg[0], bytesToSendBL2, nullptr, 0)) { - if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error - } - } - } - Motor[chan].RoundCount++; + } else { + /* + * New BL-Ctrl 11Bit served. Version >= 2.0 + */ + msg[0] = Motor[chan].SetPoint; + msg[1] = Motor[chan].SetPointLowerBits; + + if (Motor[chan].SetPointLowerBits == 0) { + bytesToSendBL2 = 1; // if setpoint lower bits are zero, we send only the higher bits - this saves time + } + + if (Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], bytesToSendBL2, &result[0], 3)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = result[2]; + + } else { + if ((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + + Motor[chan].RoundCount = 0; + + } else { + if (OK != transfer(&msg[0], bytesToSendBL2, nullptr, 0)) { + if ((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + } + + } + + Motor[chan].RoundCount++; //} - if(showDebug == true) { + if (showDebug == true) { debugCounter++; - if(debugCounter == 2000) { + + if (debugCounter == 2000) { debugCounter = 0; - for(int i=0; i<_num_outputs; i++){ - if(Motor[i].State & MOTOR_STATE_PRESENT_MASK) { + + for (int i = 0; i < _num_outputs; i++) { + if (Motor[i].State & MOTOR_STATE_PRESENT_MASK) { fprintf(stderr, "[mkblctrl] #%i:\tVer: %i\tVal: %i\tCurr: %i\tMaxPWM: %i\tTemp: %i\tState: %i\n", i, Motor[i].Version, Motor[i].SetPoint, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature, Motor[i].State); } } + fprintf(stderr, "\n"); } } + return 0; } int -MK::mk_servo_set_test(unsigned int chan, float val) +MK::mk_servo_set_value(unsigned int chan, short val) { _retries = 0; int ret; + short tmpVal = 0; + uint8_t msg[2] = { 0, 0 }; - float tmpVal = 0; + tmpVal = val; - uint8_t msg[2] = { 0,0 }; + if (tmpVal > 1024) { + tmpVal = 1024; - tmpVal = (1023 + (1023 * val)); - if(tmpVal > 2048) { - tmpVal = 2048; + } else if (tmpVal < 0) { + tmpVal = 0; } - Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); + Motor[chan].SetPoint = (uint8_t)(tmpVal / 4); - if(_armed == false) { + if (_armed == false) { Motor[chan].SetPoint = 0; Motor[chan].SetPointLowerBits = 0; } @@ -860,7 +860,6 @@ MK::mk_servo_set_test(unsigned int chan, float val) ret = transfer(&msg[0], 1, nullptr, 0); ret = OK; - return ret; } @@ -868,59 +867,61 @@ MK::mk_servo_set_test(unsigned int chan, float val) int MK::mk_servo_test(unsigned int chan) { - int ret=0; + int ret = 0; float tmpVal = 0; float val = -1; _retries = 0; - uint8_t msg[2] = { 0,0 }; + uint8_t msg[2] = { 0, 0 }; - if(debugCounter >= MOTOR_SPINUP_COUNTER) { + if (debugCounter >= MOTOR_SPINUP_COUNTER) { debugCounter = 0; _motor++; - if(_motor < _num_outputs) { + if (_motor < _num_outputs) { fprintf(stderr, "[mkblctrl] Motortest - #%i:\tspinup\n", _motor); } - if(_motor >= _num_outputs) { + if (_motor >= _num_outputs) { _motor = -1; _motortest = false; } - } + debugCounter++; - if(_motor == chan) { + if (_motor == chan) { val = BLCTRL_MIN_VALUE; + } else { val = -1; } - tmpVal = (1023 + (1023 * val)); - if(tmpVal > 2048) { - tmpVal = 2048; + tmpVal = (511 + (511 * val)); + + if (tmpVal > 1024) { + tmpVal = 1024; } - //Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); - //Motor[chan].SetPointLowerBits = (uint8_t) (tmpVal % 8) & 0x07; - Motor[chan].SetPoint = (uint8_t) tmpVal>>3; - Motor[chan].SetPointLowerBits = (uint8_t) tmpVal & 0x07; + Motor[chan].SetPoint = (uint8_t)(tmpVal / 4); - if(_motor != chan) { + if (_motor != chan) { Motor[chan].SetPoint = 0; Motor[chan].SetPointLowerBits = 0; } - if(Motor[chan].Version == BLCTRL_OLD) { + if (Motor[chan].Version == BLCTRL_OLD) { msg[0] = Motor[chan].SetPoint; + } else { msg[0] = Motor[chan].SetPoint; msg[1] = Motor[chan].SetPointLowerBits; } set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); - if(Motor[chan].Version == BLCTRL_OLD) { + + if (Motor[chan].Version == BLCTRL_OLD) { ret = transfer(&msg[0], 1, nullptr, 0); + } else { ret = transfer(&msg[0], 2, nullptr, 0); } @@ -931,9 +932,9 @@ MK::mk_servo_test(unsigned int chan) int MK::control_callback(uintptr_t handle, - uint8_t control_group, - uint8_t control_index, - float &input) + uint8_t control_group, + uint8_t control_index, + float &input) { const actuator_controls_s *controls = (actuator_controls_s *)handle; @@ -947,7 +948,6 @@ MK::ioctl(file *filp, int cmd, unsigned long arg) int ret; // XXX disabled, confusing users - //debug("ioctl 0x%04x 0x%08x", cmd, arg); /* try it as a GPIO ioctl first */ ret = gpio_ioctl(filp, cmd, arg); @@ -978,32 +978,37 @@ int MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) { int ret = OK; - int channel; lock(); switch (cmd) { case PWM_SERVO_ARM: - ////up_pwm_servo_arm(true); mk_servo_arm(true); break; + case PWM_SERVO_SET_ARM_OK: + case PWM_SERVO_CLEAR_ARM_OK: + // these are no-ops, as no safety switch + break; + case PWM_SERVO_DISARM: - ////up_pwm_servo_arm(false); mk_servo_arm(false); break; case PWM_SERVO_SET_UPDATE_RATE: - set_pwm_rate(arg); + ret = OK; + break; + + case PWM_SERVO_SELECT_UPDATE_RATE: + ret = OK; break; case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1): + if (arg < 2150) { + Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg; + mk_servo_set_value(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 1024)); - /* fake an update to the selected 'servo' channel */ - if ((arg >= 0) && (arg <= 255)) { - channel = cmd - PWM_SERVO_SET(0); - //mk_servo_set(channel, arg); } else { ret = -EINVAL; } @@ -1012,20 +1017,20 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1): /* copy the current output value from the channel */ - *(servo_position_t *)arg = cmd - PWM_SERVO_GET(0); + *(servo_position_t *)arg = Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue; + break; + case PWM_SERVO_GET_RATEGROUP(0): + case PWM_SERVO_GET_RATEGROUP(1): + case PWM_SERVO_GET_RATEGROUP(2): + case PWM_SERVO_GET_RATEGROUP(3): + //*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0)); + break; + + case PWM_SERVO_GET_COUNT: case MIXERIOCGETOUTPUTCOUNT: - /* - if (_mode == MODE_4PWM) { - *(unsigned *)arg = 4; - } else { - *(unsigned *)arg = 2; - } - */ - *(unsigned *)arg = _num_outputs; - break; case MIXERIOCRESET: @@ -1078,6 +1083,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) ret = -EINVAL; } } + break; } @@ -1091,6 +1097,32 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) return ret; } +/* + this implements PWM output via a write() method, for compatibility + with px4io + */ +ssize_t +MK::write(file *filp, const char *buffer, size_t len) +{ + unsigned count = len / 2; + uint16_t values[4]; + + if (count > 4) { + // we only have 4 PWM outputs on the FMU + count = 4; + } + + // allow for misaligned values + memcpy(values, buffer, count * 2); + + for (uint8_t i = 0; i < count; i++) { + Motor[i].RawPwmValue = (unsigned short)values[i]; + mk_servo_set_value(i, scaling(values[i], 1010, 2100, 0, 1024)); + } + + return count * 2; +} + void MK::gpio_reset(void) { @@ -1229,10 +1261,10 @@ enum MappingMode { MAPPING_PX4, }; - enum FrameType { - FRAME_PLUS = 0, - FRAME_X, - }; +enum FrameType { + FRAME_PLUS = 0, + FRAME_X, +}; PortMode g_port_mode; @@ -1297,18 +1329,17 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, g_mk->set_motor_test(motortest); - /* (re)set count of used motors */ - ////g_mk->set_motor_count(motorcount); /* count used motors */ - do { - if(g_mk->mk_check_for_blctrl(8, false) != 0) { + if (g_mk->mk_check_for_blctrl(8, false) != 0) { shouldStop = 4; + } else { shouldStop++; } + sleep(1); - } while ( shouldStop < 3); + } while (shouldStop < 3); g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true)); @@ -1375,7 +1406,8 @@ mkblctrl_main(int argc, char *argv[]) if (argc > i + 1) { bus = atoi(argv[i + 1]); newMode = true; - } else { + + } else { errx(1, "missing argument for i2c bus (-b)"); return 1; } @@ -1384,17 +1416,21 @@ mkblctrl_main(int argc, char *argv[]) /* look for the optional frame parameter */ if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) { if (argc > i + 1) { - if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { + if (strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { px4mode = MAPPING_MK; newMode = true; - if(strcmp(argv[i + 1], "+") == 0) { + + if (strcmp(argv[i + 1], "+") == 0) { frametype = FRAME_PLUS; + } else { frametype = FRAME_X; } + } else { errx(1, "only + or x for frametype supported !"); } + } else { errx(1, "missing argument for mkmode (-mkmode)"); return 1; @@ -1409,12 +1445,12 @@ mkblctrl_main(int argc, char *argv[]) /* look for the optional -h --help parameter */ if (strcmp(argv[i], "-h") == 0 || strcmp(argv[i], "--help") == 0) { - showHelp == true; + showHelp = true; } } - if(showHelp) { + if (showHelp) { fprintf(stderr, "mkblctrl: help:\n"); fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n"); exit(1); @@ -1424,6 +1460,7 @@ mkblctrl_main(int argc, char *argv[]) if (g_mk == nullptr) { if (mk_start(bus, motorcount) != OK) { errx(1, "failed to start the MK-BLCtrl driver"); + } else { newMode = true; } From 318d2baba013c946401f0b1879b02c19b6b03aae Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 23 May 2013 23:58:25 +0200 Subject: [PATCH 25/89] Reinstate mapfile generation. --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 874e7154c7..74f6b2a89f 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -235,7 +235,7 @@ endef define LINK @$(ECHO) "LINK: $1" @$(MKDIR) -p $(dir $1) - $(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group + $(Q) $(LD) $(LDFLAGS) -Map $1.map -o $1 --start-group $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group endef # Convert $1 from a linked object to a raw binary in $2 From f30695e1df3e9d7811ae460be5ec69c70cc15e69 Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 23 May 2013 23:58:59 +0200 Subject: [PATCH 26/89] Hotfix: fix section attribute for the ROMFS, moving it back into .rodata where it belongs. --- makefiles/toolchain_gnu-arm-eabi.mk | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 74f6b2a89f..eeba0ff2c6 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -280,6 +280,7 @@ define BIN_TO_OBJ $(Q) $(OBJCOPY) $2 \ --redefine-sym $(call BIN_SYM_PREFIX,$1)_start=$3 \ --redefine-sym $(call BIN_SYM_PREFIX,$1)_size=$3_len \ - --strip-symbol $(call BIN_SYM_PREFIX,$1)_end + --strip-symbol $(call BIN_SYM_PREFIX,$1)_end \ + --rename-section .data=.rodata $(Q) $(REMOVE) $2.c $2.c.o endef From 8e1571cf0230ff31cbbb1af64a793c3957827cc2 Mon Sep 17 00:00:00 2001 From: marco Date: Fri, 24 May 2013 20:16:47 +0200 Subject: [PATCH 27/89] mkblctrl cleanup & tested --- src/drivers/mkblctrl/mkblctrl.cpp | 31 ++++++++++++++++++++++++------- 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index f6e4e0ed3e..4220f552e4 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -491,8 +491,10 @@ MK::task_main() * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. */ - _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : - ORB_ID(actuator_controls_0)); + // loeschen _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : + // loeschen ORB_ID(actuator_controls_0)); + _t_actuators = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + /* force a reset of the update rate */ _current_update_rate = 0; @@ -502,11 +504,19 @@ MK::task_main() /* advertise the mixed control outputs */ actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); + /* advertise the mixed control outputs */ + _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), + &outputs); + + /* advertise the effective control inputs */ actuator_controls_effective_s controls_effective; memset(&controls_effective, 0, sizeof(controls_effective)); /* advertise the effective control inputs */ + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), + &controls_effective); + pollfd fds[2]; fds[0].fd = _t_actuators; @@ -556,7 +566,8 @@ MK::task_main() if (fds[0].revents & POLLIN) { /* get controls - must always do this to avoid spinning */ - orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_0), _t_actuators, &_controls); + // loeschen orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_0), _t_actuators, &_controls); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls); /* can we mix? */ if (_mixers != nullptr) { @@ -1105,13 +1116,19 @@ ssize_t MK::write(file *filp, const char *buffer, size_t len) { unsigned count = len / 2; - uint16_t values[4]; + // loeschen uint16_t values[4]; + uint16_t values[8]; - if (count > 4) { - // we only have 4 PWM outputs on the FMU - count = 4; + // loeschen if (count > 4) { + // loeschen // we only have 4 PWM outputs on the FMU + // loeschen count = 4; + // loeschen } + if (count > _num_outputs) { + // we only have 8 I2C outputs in the driver + count = _num_outputs; } + // allow for misaligned values memcpy(values, buffer, count * 2); From 214ddd6f1ca12bf52d533aba791877d9cdfe6345 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 25 May 2013 18:16:15 +0200 Subject: [PATCH 28/89] Adjusted example params and extensively commented example --- src/examples/fixedwing_control/main.c | 97 ++++++++++++++++++++----- src/examples/fixedwing_control/params.c | 2 +- 2 files changed, 80 insertions(+), 19 deletions(-) diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 6a9ad9e1d1..a1b9c78f9e 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -73,8 +73,15 @@ #include "params.h" /* Prototypes */ + /** * Daemon management function. + * + * This function allows to start / stop the background task (daemon). + * The purpose of it is to be able to start the controller on the + * command line, query its status and stop it, without giving up + * the command line to one particular process or the need for bg/fg + * ^Z support by the shell. */ __EXPORT int ex_fixedwing_control_main(int argc, char *argv[]); @@ -88,10 +95,34 @@ int fixedwing_control_thread_main(int argc, char *argv[]); */ static void usage(const char *reason); +/** + * Control roll and pitch angle. + * + * This very simple roll and pitch controller takes the current roll angle + * of the system and compares it to a reference. Pitch is controlled to zero and yaw remains + * uncontrolled (tutorial code, not intended for flight). + * + * @param att_sp The current attitude setpoint - the values the system would like to reach. + * @param att The current attitude. The controller should make the attitude match the setpoint + * @param speed_body The velocity of the system. Currently unused. + * @param rates_sp The angular rate setpoint. This is the output of the controller. + */ void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, - float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + float speed_body[], struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators); +/** + * Control heading. + * + * This very simple heading to roll angle controller outputs the desired roll angle based on + * the current position of the system, the desired position (the setpoint) and the current + * heading. + * + * @param pos The current position of the system + * @param sp The current position setpoint + * @param att The current attitude + * @param att_sp The attitude setpoint. This is the output of the controller + */ void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp, const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp); @@ -103,7 +134,7 @@ static struct params p; static struct param_handles ph; void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, - float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + float speed_body[], struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators) { @@ -148,7 +179,10 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct v * Calculate heading error of current position to desired position */ - /* PX4 uses 1e7 scaled integers to represent global coordinates for max resolution */ + /* + * PX4 uses 1e7 scaled integers to represent global coordinates for max resolution, + * so they need to be scaled by 1e7 and converted to IEEE double precision floating point. + */ float bearing = get_bearing_to_next_waypoint(pos->lat/1e7d, pos->lon/1e7d, sp->lat/1e7d, sp->lon/1e7d); /* calculate heading error */ @@ -157,10 +191,10 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct v float roll_command = yaw_err * p.hdng_p; /* limit output, this commonly is a tuning parameter, too */ - if (att_sp->roll_body < -0.5f) { - att_sp->roll_body = -0.5f; - } else if (att_sp->roll_body > 0.5f) { - att_sp->roll_body = 0.5f; + if (att_sp->roll_body < -0.6f) { + att_sp->roll_body = -0.6f; + } else if (att_sp->roll_body > 0.6f) { + att_sp->roll_body = 0.6f; } } @@ -183,7 +217,32 @@ int fixedwing_control_thread_main(int argc, char *argv[]) parameters_init(&ph); parameters_update(&ph, &p); - /* declare and safely initialize all structs to zero */ + + /* + * PX4 uses a publish/subscribe design pattern to enable + * multi-threaded communication. + * + * The most elegant aspect of this is that controllers and + * other processes can either 'react' to new data, or run + * at their own pace. + * + * PX4 developer guide: + * https://pixhawk.ethz.ch/px4/dev/shared_object_communication + * + * Wikipedia description: + * http://en.wikipedia.org/wiki/Publish–subscribe_pattern + * + */ + + + + + /* + * Declare and safely initialize all structs to zero. + * + * These structs contain the system state and things + * like attitude, position, the current waypoint, etc. + */ struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; @@ -199,20 +258,24 @@ int fixedwing_control_thread_main(int argc, char *argv[]) struct vehicle_global_position_setpoint_s global_sp; memset(&global_sp, 0, sizeof(global_sp)); - /* output structs */ + /* output structs - this is what is sent to the mixer */ struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); - /* publish actuator controls */ + /* publish actuator controls with zero values */ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) { actuators.control[i] = 0.0f; } + /* + * Advertise that this controller will publish actuator + * control values and the rate setpoint + */ orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); - /* subscribe */ + /* subscribe to topics. */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); @@ -222,7 +285,6 @@ int fixedwing_control_thread_main(int argc, char *argv[]) int param_sub = orb_subscribe(ORB_ID(parameter_update)); /* Setup of loop */ - float gyro[3] = {0.0f, 0.0f, 0.0f}; float speed_body[3] = {0.0f, 0.0f, 0.0f}; struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN }, { .fd = att_sub, .events = POLLIN }}; @@ -275,6 +337,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) if (global_sp_updated) orb_copy(ORB_ID(vehicle_global_position_setpoint), global_sp_sub, &global_sp); + /* currently speed in body frame is not used, but here for reference */ if (pos_updated) { orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); @@ -292,13 +355,11 @@ int fixedwing_control_thread_main(int argc, char *argv[]) } } + /* get the RC (or otherwise user based) input */ orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); + /* get the system status and the flight mode we're in */ orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); - gyro[0] = att.rollspeed; - gyro[1] = att.pitchspeed; - gyro[2] = att.yawspeed; - /* control */ if (vstatus.state_machine == SYSTEM_STATE_AUTO || @@ -312,7 +373,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) actuators.control[2] = 0.0f; /* simple attitude control */ - control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators); /* pass through throttle */ actuators.control[3] = att_sp.thrust; @@ -355,7 +416,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) att_sp.timestamp = hrt_absolute_time(); /* attitude control */ - control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators); /* pass through throttle */ actuators.control[3] = att_sp.thrust; diff --git a/src/examples/fixedwing_control/params.c b/src/examples/fixedwing_control/params.c index 8042c74f5e..c2e94ff3d3 100644 --- a/src/examples/fixedwing_control/params.c +++ b/src/examples/fixedwing_control/params.c @@ -45,7 +45,7 @@ /** * */ -PARAM_DEFINE_FLOAT(EXFW_HDNG_P, 0.2f); +PARAM_DEFINE_FLOAT(EXFW_HDNG_P, 0.1f); /** * From bc7a7167ae955a810299831a8504bac7c9cd60fb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 25 May 2013 18:21:39 +0200 Subject: [PATCH 29/89] Go only to RC failsafe if throttle was half once - to prevent failsafe when armed on ground --- src/examples/fixedwing_control/main.c | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index a1b9c78f9e..9fd11062a7 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -286,6 +286,8 @@ int fixedwing_control_thread_main(int argc, char *argv[]) /* Setup of loop */ float speed_body[3] = {0.0f, 0.0f, 0.0f}; + /* RC failsafe check */ + bool throttle_half_once = false; struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN }, { .fd = att_sub, .events = POLLIN }}; @@ -357,6 +359,14 @@ int fixedwing_control_thread_main(int argc, char *argv[]) /* get the RC (or otherwise user based) input */ orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); + + /* check if the throttle was ever more than 50% - go only to failsafe if yes */ + if (isfinite(manual_sp.throttle) && + (manual_sp.throttle >= 0.6f) && + (manual_sp.throttle <= 1.0f)) { + throttle_half_once = true; + } + /* get the system status and the flight mode we're in */ orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); @@ -385,7 +395,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if (vstatus.rc_signal_lost) { + if (vstatus.rc_signal_lost && throttle_half_once) { /* put plane into loiter */ att_sp.roll_body = 0.3f; From e2113526043f82700c2cff5d16d9e3a4dee089c7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 25 May 2013 22:15:56 +0400 Subject: [PATCH 30/89] sdlog2 logger app added. New flexible log format, compatible with APM. --- makefiles/config_px4fmu_default.mk | 1 + src/modules/sdlog2/module.mk | 43 ++ src/modules/sdlog2/sdlog2.c | 890 +++++++++++++++++++++++++ src/modules/sdlog2/sdlog2_format.h | 98 +++ src/modules/sdlog2/sdlog2_messages.h | 82 +++ src/modules/sdlog2/sdlog2_ringbuffer.c | 141 ++++ src/modules/sdlog2/sdlog2_ringbuffer.h | 68 ++ 7 files changed, 1323 insertions(+) create mode 100644 src/modules/sdlog2/module.mk create mode 100644 src/modules/sdlog2/sdlog2.c create mode 100644 src/modules/sdlog2/sdlog2_format.h create mode 100644 src/modules/sdlog2/sdlog2_messages.h create mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.c create mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.h diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 1e4d592665..b6fa4014a2 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -78,6 +78,7 @@ MODULES += modules/multirotor_pos_control # Logging # MODULES += modules/sdlog +MODULES += modules/sdlog2 # # Library modules diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk new file mode 100644 index 0000000000..5a9936635a --- /dev/null +++ b/src/modules/sdlog2/module.mk @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (c) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# sdlog2 Application +# + +MODULE_COMMAND = sdlog2 +# The main thread only buffers to RAM, needs a high priority +MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30" + +SRCS = sdlog2.c \ + sdlog2_ringbuffer.c diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c new file mode 100644 index 0000000000..38b57082f4 --- /dev/null +++ b/src/modules/sdlog2/sdlog2.c @@ -0,0 +1,890 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2.c + * + * Simple SD logger for flight data. Buffers new sensor values and + * does the heavy SD I/O in a low-priority worker thread. + * + * @author Lorenz Meier + * @author Anton Babushkin + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include "sdlog2_ringbuffer.h" +#include "sdlog2_messages.h" + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ +static const int LOG_BUFFER_SIZE = 2048; +static const int MAX_WRITE_CHUNK = 1024; + +static const char *mountpoint = "/fs/microsd"; +int log_file = -1; +int mavlink_fd = -1; +struct sdlog2_logbuffer lb; + +/* mutex / condition to synchronize threads */ +pthread_mutex_t logbuffer_mutex; +pthread_cond_t logbuffer_cond; + +/** + * System state vector log buffer writing + */ +static void *sdlog2_logbuffer_write_thread(void *arg); + +/** + * Create the thread to write the system vector + */ +pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf); + +/** + * Write a header to log file: list of message formats + */ +void sdlog2_write_formats(int fd); + +/** + * SD log management function. + */ +__EXPORT int sdlog2_main(int argc, char *argv[]); + +/** + * Mainloop of sd log deamon. + */ +int sdlog2_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static int file_exist(const char *filename); + +static int file_copy(const char *file_old, const char *file_new); + +static void handle_command(struct vehicle_command_s *cmd); + +/** + * Print the current status. + */ +static void print_sdlog2_status(void); + +/** + * Create folder for current logging session. + */ +static int create_logfolder(char *folder_path); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + errx(1, "usage: sdlog2 {start|stop|status} [-s ]\n\n"); +} + +unsigned long log_bytes_written = 0; +uint64_t starttime = 0; + +/* logging on or off, default to true */ +bool logging_enabled = true; + +/** + * The sd log deamon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_spawn(). + */ +int sdlog2_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("sdlog2 already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn("sdlog2", + SCHED_DEFAULT, + SCHED_PRIORITY_DEFAULT - 30, + 4096, + sdlog2_thread_main, + (const char **)argv); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + if (!thread_running) { + printf("\tsdlog2 is not started\n"); + } + + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + print_sdlog2_status(); + + } else { + printf("\tsdlog2 not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int create_logfolder(char *folder_path) +{ + /* make folder on sdcard */ + uint16_t foldernumber = 1; // start with folder 0001 + int mkdir_ret; + + /* look for the next folder that does not exist */ + while (foldernumber < MAX_NO_LOGFOLDER) { + /* set up file path: e.g. /mnt/sdcard/sensorfile0001.txt */ + sprintf(folder_path, "%s/session%04u", mountpoint, foldernumber); + mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO); + /* the result is -1 if the folder exists */ + + if (mkdir_ret == 0) { + /* folder does not exist, success */ + + /* copy parser script file */ + // TODO + /* + char mfile_out[100]; + sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber); + int ret = file_copy(mfile_in, mfile_out); + + if (!ret) { + warnx("copied m file to %s", mfile_out); + + } else { + warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out); + } + */ + + break; + + } else if (mkdir_ret == -1) { + /* folder exists already */ + foldernumber++; + continue; + + } else { + warn("failed creating new folder"); + return -1; + } + } + + if (foldernumber >= MAX_NO_LOGFOLDER) { + /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ + warn("all %d possible folders exist already", MAX_NO_LOGFOLDER); + return -1; + } + + return 0; +} + +static void * +sdlog2_logbuffer_write_thread(void *arg) +{ + /* set name */ + prctl(PR_SET_NAME, "sdlog2 microSD I/O", 0); + + struct sdlog2_logbuffer *logbuf = (struct sdlog2_logbuffer *)arg; + + int poll_count = 0; + + void *read_ptr; + int n = 0; + + while (!thread_should_exit) { + + /* make sure threads are synchronized */ + pthread_mutex_lock(&logbuffer_mutex); + + /* update read pointer if needed */ + if (n > 0) { + sdlog2_logbuffer_mark_read(&lb, n); + } + + /* only wait if no data is available to process */ + if (sdlog2_logbuffer_is_empty(logbuf)) { + /* blocking wait for new data at this line */ + pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex); + } + + /* only get pointer to thread-safe data, do heavy I/O a few lines down */ + n = sdlog2_logbuffer_get_ptr(logbuf, &read_ptr); + + /* continue */ + pthread_mutex_unlock(&logbuffer_mutex); + + if (n > 0) { + /* do heavy IO here */ + if (n > MAX_WRITE_CHUNK) + n = MAX_WRITE_CHUNK; + + n = write(log_file, read_ptr, n); + + if (n > 0) { + log_bytes_written += n; + } + } + + if (poll_count % 100 == 0) { + fsync(log_file); + } + + poll_count++; + } + + fsync(log_file); + + return OK; +} + +pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) +{ + pthread_attr_t receiveloop_attr; + pthread_attr_init(&receiveloop_attr); + + struct sched_param param; + /* low priority, as this is expensive disk I/O */ + param.sched_priority = SCHED_PRIORITY_DEFAULT - 40; + (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); + + pthread_attr_setstacksize(&receiveloop_attr, 2048); + + pthread_t thread; + pthread_create(&thread, &receiveloop_attr, sdlog2_logbuffer_write_thread, logbuf); + return thread; + + // XXX we have to destroy the attr at some point +} + +void sdlog2_write_formats(int fd) +{ + /* construct message format packet */ + struct { + LOG_PACKET_HEADER; + struct log_format_s body; + } log_format_packet = { + LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG), + }; + + /* fill message format packet for each format and write to log */ + int i; + + for (i = 0; i < log_formats_num; i++) { + log_format_packet.body = log_formats[i]; + write(fd, &log_format_packet, sizeof(log_format_packet)); + } + + fsync(fd); +} + +int sdlog2_thread_main(int argc, char *argv[]) +{ + mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); + + if (mavlink_fd < 0) { + warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); + } + + /* log every n'th value (skip three per default) */ + int skip_value = 3; + + /* work around some stupidity in task_create's argv handling */ + argc -= 2; + argv += 2; + int ch; + + while ((ch = getopt(argc, argv, "s:r")) != EOF) { + switch (ch) { + case 's': { + /* log only every n'th (gyro clocked) value */ + unsigned s = strtoul(optarg, NULL, 10); + + if (s < 1 || s > 250) { + errx(1, "Wrong skip value of %d, out of range (1..250)\n", s); + + } else { + skip_value = s; + } + } + break; + + case 'r': + /* log only on request, disable logging per default */ + logging_enabled = false; + break; + + case '?': + if (optopt == 'c') { + warnx("Option -%c requires an argument.\n", optopt); + + } else if (isprint(optopt)) { + warnx("Unknown option `-%c'.\n", optopt); + + } else { + warnx("Unknown option character `\\x%x'.\n", optopt); + } + + default: + usage("unrecognized flag"); + errx(1, "exiting."); + } + } + + if (file_exist(mountpoint) != OK) { + errx(1, "logging mount point %s not present, exiting.", mountpoint); + } + + char folder_path[64]; + + if (create_logfolder(folder_path)) + errx(1, "unable to create logging folder, exiting."); + + /* string to hold the path to the sensorfile */ + char path_buf[64] = ""; + + /* only print logging path, important to find log file later */ + warnx("logging to directory %s\n", folder_path); + + /* set up file path: e.g. /mnt/sdcard/session0001/actuator_controls0.bin */ + sprintf(path_buf, "%s/%s.bin", folder_path, "log"); + + if (0 == (log_file = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC))) { + errx(1, "opening %s failed.\n", path_buf); + } + + /* write log messages formats */ + sdlog2_write_formats(log_file); + + /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ + /* number of messages */ + const ssize_t fdsc = 25; + /* Sanity check variable and index */ + ssize_t fdsc_count = 0; + /* file descriptors to wait for */ + struct pollfd fds[fdsc]; + + /* warning! using union here to save memory, elements should be used separately! */ + union { + struct sensor_combined_s raw; + struct vehicle_attitude_s att; + struct vehicle_attitude_setpoint_s att_sp; + struct actuator_outputs_s act_outputs; + struct actuator_controls_s act_controls; + struct actuator_controls_effective_s act_controls_effective; + struct vehicle_command_s cmd; + struct vehicle_local_position_s local_pos; + struct vehicle_global_position_s global_pos; + struct vehicle_gps_position_s gps_pos; + struct vehicle_vicon_position_s vicon_pos; + struct optical_flow_s flow; + struct battery_status_s batt; + struct differential_pressure_s diff_pres; + struct airspeed_s airspeed; + } buf; + memset(&buf, 0, sizeof(buf)); + + struct { + int cmd_sub; + int sensor_sub; + int att_sub; + int att_sp_sub; + int act_0_sub; + int controls_0_sub; + int controls_effective_0_sub; + int local_pos_sub; + int global_pos_sub; + int gps_pos_sub; + int vicon_pos_sub; + int flow_sub; + int batt_sub; + int diff_pres_sub; + int airspeed_sub; + } subs; + + /* log message buffer: header + body */ + struct { + LOG_PACKET_HEADER; + union { + struct log_TS_s log_TS; + struct log_ATT_s log_ATT; + struct log_RAW_s log_RAW; + } body; + } log_msg = { + LOG_PACKET_HEADER_INIT(0) + }; + memset(&log_msg.body, 0, sizeof(log_msg.body)); + + /* --- MANAGEMENT - LOGGING COMMAND --- */ + /* subscribe to ORB for vehicle command */ + subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds[fdsc_count].fd = subs.cmd_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- GPS POSITION --- */ + /* subscribe to ORB for global position */ + subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + fds[fdsc_count].fd = subs.gps_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- SENSORS RAW VALUE --- */ + /* subscribe to ORB for sensors raw */ + subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + fds[fdsc_count].fd = subs.sensor_sub; + /* do not rate limit, instead use skip counter (aliasing on rate limit) */ + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ATTITUDE VALUE --- */ + /* subscribe to ORB for attitude */ + subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + fds[fdsc_count].fd = subs.att_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ATTITUDE SETPOINT VALUE --- */ + /* subscribe to ORB for attitude setpoint */ + /* struct already allocated */ + subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + fds[fdsc_count].fd = subs.att_sp_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /** --- ACTUATOR OUTPUTS --- */ + subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); + fds[fdsc_count].fd = subs.act_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ACTUATOR CONTROL VALUE --- */ + /* subscribe to ORB for actuator control */ + subs.controls_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + fds[fdsc_count].fd = subs.controls_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* subscribe to ORB for actuator control */ + subs.controls_effective_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); + fds[fdsc_count].fd = subs.controls_effective_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- LOCAL POSITION --- */ + /* subscribe to ORB for local position */ + subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); + fds[fdsc_count].fd = subs.local_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- GLOBAL POSITION --- */ + /* subscribe to ORB for global position */ + subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); + fds[fdsc_count].fd = subs.global_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- VICON POSITION --- */ + /* subscribe to ORB for vicon position */ + subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position)); + fds[fdsc_count].fd = subs.vicon_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- FLOW measurements --- */ + /* subscribe to ORB for flow measurements */ + subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); + fds[fdsc_count].fd = subs.flow_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- BATTERY STATUS --- */ + /* subscribe to ORB for flow measurements */ + subs.batt_sub = orb_subscribe(ORB_ID(battery_status)); + fds[fdsc_count].fd = subs.batt_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- DIFFERENTIAL PRESSURE --- */ + /* subscribe to ORB for flow measurements */ + subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); + fds[fdsc_count].fd = subs.diff_pres_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- AIRSPEED --- */ + /* subscribe to ORB for airspeed */ + subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed)); + fds[fdsc_count].fd = subs.airspeed_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* WARNING: If you get the error message below, + * then the number of registered messages (fdsc) + * differs from the number of messages in the above list. + */ + if (fdsc_count > fdsc) { + warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.\n", __FILE__, __LINE__); + fdsc_count = fdsc; + } + + /* + * set up poll to block for new data, + * wait for a maximum of 1000 ms (1 second) + */ + // const int timeout = 1000; + + thread_running = true; + + /* initialize log buffer with specified size */ + sdlog2_logbuffer_init(&lb, LOG_BUFFER_SIZE); + + /* initialize thread synchronization */ + pthread_mutex_init(&logbuffer_mutex, NULL); + pthread_cond_init(&logbuffer_cond, NULL); + + /* start logbuffer emptying thread */ + pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); + + starttime = hrt_absolute_time(); + + /* track skipping */ + int skip_count = 0; + + while (!thread_should_exit) { + + /* poll all topics */ + int poll_ret = poll(fds, 4, 1000); + + /* handle the poll result */ + if (poll_ret == 0) { + /* XXX this means none of our providers is giving us data - might be an error? */ + } else if (poll_ret < 0) { + /* XXX this is seriously bad - should be an emergency */ + } else { + + int ifds = 0; + + if (!logging_enabled) { + usleep(100000); + continue; + } + + pthread_mutex_lock(&logbuffer_mutex); + + /* write time stamp message */ + log_msg.msg_type = LOG_TS_MSG; + log_msg.body.log_TS.t = hrt_absolute_time(); + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TS)); + + /* --- VEHICLE COMMAND VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + /* copy command into local buffer */ + orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); + handle_command(&buf.cmd); + } + + /* --- GPS POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + } + + /* --- SENSORS RAW VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw); + log_msg.msg_type = LOG_RAW_MSG; + log_msg.body.log_RAW.accX = buf.raw.accelerometer_m_s2[0]; + log_msg.body.log_RAW.accY = buf.raw.accelerometer_m_s2[1]; + log_msg.body.log_RAW.accZ = buf.raw.accelerometer_m_s2[2]; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(RAW)); + } + + /* --- ATTITUDE VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att); + log_msg.msg_type = LOG_ATT_MSG; + log_msg.body.log_ATT.roll = buf.att.roll; + log_msg.body.log_ATT.pitch = buf.att.pitch; + log_msg.body.log_ATT.yaw = buf.att.yaw; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); + } + + /* --- ATTITUDE SETPOINT VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp); + // TODO not implemented yet + } + + /* --- ACTUATOR OUTPUTS --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- ACTUATOR CONTROL VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- LOCAL POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- GLOBAL POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- VICON POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- FLOW measurements --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- BATTERY STATUS --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- DIFFERENTIAL PRESSURE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- AIRSPEED --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* signal the other thread new data, but not yet unlock */ + if (sdlog2_logbuffer_count(&lb) > (lb.size / 2)) { + /* only request write if several packets can be written at once */ + pthread_cond_signal(&logbuffer_cond); + } + + /* unlock, now the writer thread may run */ + pthread_mutex_unlock(&logbuffer_mutex); + } + } + + print_sdlog2_status(); + + /* wake up write thread one last time */ + pthread_mutex_lock(&logbuffer_mutex); + pthread_cond_signal(&logbuffer_cond); + /* unlock, now the writer thread may return */ + pthread_mutex_unlock(&logbuffer_mutex); + + /* wait for write thread to return */ + (void)pthread_join(logwriter_pthread, NULL); + + pthread_mutex_destroy(&logbuffer_mutex); + pthread_cond_destroy(&logbuffer_cond); + + warnx("exiting.\n\n"); + + thread_running = false; + + return 0; +} + +void print_sdlog2_status() +{ + float mebibytes = log_bytes_written / 1024.0f / 1024.0f; + float seconds = ((float)(hrt_absolute_time() - starttime)) / 1000000.0f; + + warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); +} + +/** + * @return 0 if file exists + */ +int file_exist(const char *filename) +{ + struct stat buffer; + return stat(filename, &buffer); +} + +int file_copy(const char *file_old, const char *file_new) +{ + FILE *source, *target; + source = fopen(file_old, "r"); + int ret = 0; + + if (source == NULL) { + warnx("failed opening input file to copy"); + return 1; + } + + target = fopen(file_new, "w"); + + if (target == NULL) { + fclose(source); + warnx("failed to open output file to copy"); + return 1; + } + + char buf[128]; + int nread; + + while ((nread = fread(buf, 1, sizeof(buf), source)) > 0) { + ret = fwrite(buf, 1, nread, target); + + if (ret <= 0) { + warnx("error writing file"); + ret = 1; + break; + } + } + + fsync(fileno(target)); + + fclose(source); + fclose(target); + + return ret; +} + +void handle_command(struct vehicle_command_s *cmd) +{ + /* result of the command */ + uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED; + + /* request to set different system mode */ + switch (cmd->command) { + + case VEHICLE_CMD_PREFLIGHT_STORAGE: + + if (((int)(cmd->param3)) == 1) { + + /* enable logging */ + mavlink_log_info(mavlink_fd, "[log] file:"); + mavlink_log_info(mavlink_fd, "logdir"); + logging_enabled = true; + } + + if (((int)(cmd->param3)) == 0) { + + /* disable logging */ + mavlink_log_info(mavlink_fd, "[log] stopped."); + logging_enabled = false; + } + + break; + + default: + /* silently ignore */ + break; + } + +} diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h new file mode 100644 index 0000000000..f5347a7bdd --- /dev/null +++ b/src/modules/sdlog2/sdlog2_format.h @@ -0,0 +1,98 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_format.h + * + * General log format structures and macro. + * + * @author Anton Babushkin + */ + +/* +Format characters in the format string for binary log messages + b : int8_t + B : uint8_t + h : int16_t + H : uint16_t + i : int32_t + I : uint32_t + f : float + n : char[4] + N : char[16] + Z : char[64] + c : int16_t * 100 + C : uint16_t * 100 + e : int32_t * 100 + E : uint32_t * 100 + L : int32_t latitude/longitude + M : uint8_t flight mode + + q : int64_t + Q : uint64_t + */ + +#ifndef SDLOG2_FORMAT_H_ +#define SDLOG2_FORMAT_H_ + +#define LOG_PACKET_HEADER_LEN 3 +#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type; +#define LOG_PACKET_HEADER_INIT(id) .head1 = HEAD_BYTE1, .head2 = HEAD_BYTE2, .msg_type = id + +// once the logging code is all converted we will remove these from +// this header +#define HEAD_BYTE1 0xA3 // Decimal 163 +#define HEAD_BYTE2 0x95 // Decimal 149 + +struct log_format_s { + uint8_t type; + uint8_t length; + char name[4]; + char format[16]; + char labels[64]; +}; + +#define LOG_FORMAT(_name, _format, _labels) { \ + .type = LOG_##_name##_MSG, \ + .length = sizeof(struct log_##_name##_s) + 8, \ + .name = #_name, \ + .format = _format, \ + .labels = _labels \ + } + +#define LOG_FORMAT_MSG 128 + +#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) + +#endif /* SDLOG2_FORMAT_H_ */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h new file mode 100644 index 0000000000..ae98ea0381 --- /dev/null +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_messages.h + * + * Log messages and structures definition. + * + * @author Anton Babushkin + */ + +#ifndef SDLOG2_MESSAGES_H_ +#define SDLOG2_MESSAGES_H_ + +#include "sdlog2_format.h" + +/* define message formats */ + +/* === 1: TS - TIME STAMP === */ +#define LOG_TS_MSG 1 +struct log_TS_s { + uint64_t t; +}; + +/* === 2: ATT - ATTITUDE === */ +#define LOG_ATT_MSG 2 +struct log_ATT_s { + float roll; + float pitch; + float yaw; +}; + +/* === 3: RAW - SENSORS === */ +#define LOG_RAW_MSG 3 +struct log_RAW_s { + float accX; + float accY; + float accZ; +}; + +/* construct list of all message formats */ + +static const struct log_format_s log_formats[] = { + LOG_FORMAT(TS, "Q", "t"), + LOG_FORMAT(ATT, "fff", "roll,pitch,yaw"), + LOG_FORMAT(RAW, "fff", "accX,accY,accZ"), +}; + +static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); + +#endif /* SDLOG2_MESSAGES_H_ */ diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.c b/src/modules/sdlog2/sdlog2_ringbuffer.c new file mode 100644 index 0000000000..022a183ba3 --- /dev/null +++ b/src/modules/sdlog2/sdlog2_ringbuffer.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_ringbuffer.c + * + * Ring FIFO buffer for binary data. + * + * @author Anton Babushkin + */ + +#include +#include + +#include "sdlog2_ringbuffer.h" + +void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size) +{ + lb->size = size; + lb->write_ptr = 0; + lb->read_ptr = 0; + lb->data = malloc(lb->size); +} + +int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb) +{ + int n = lb->read_ptr - lb->write_ptr - 1; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb) +{ + int n = lb->write_ptr - lb->read_ptr; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb) +{ + return lb->read_ptr == lb->write_ptr; +} + +void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) +{ + // bytes available to write + int available = lb->read_ptr - lb->write_ptr - 1; + + if (available < 0) + available += lb->size; + + if (size > available) { + // buffer overflow + return; + } + + char *c = (char *) ptr; + int n = lb->size - lb->write_ptr; // bytes to end of the buffer + + if (n < size) { + // message goes over end of the buffer + memcpy(&(lb->data[lb->write_ptr]), c, n); + lb->write_ptr = 0; + + } else { + n = 0; + } + + // now: n = bytes already written + int p = size - n; // number of bytes to write + memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p); + lb->write_ptr = (lb->write_ptr + p) % lb->size; +} + +int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr) +{ + // bytes available to read + int available = lb->write_ptr - lb->read_ptr; + + if (available == 0) { + return 0; // buffer is empty + } + + int n = 0; + + if (available > 0) { + // read pointer is before write pointer, write all available bytes + n = available; + + } else { + // read pointer is after write pointer, write bytes from read_ptr to end + n = lb->size - lb->read_ptr; + } + + *ptr = &(lb->data[lb->read_ptr]); + return n; +} + +void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n) +{ + lb->read_ptr = (lb->read_ptr + n) % lb->size; +} diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.h b/src/modules/sdlog2/sdlog2_ringbuffer.h new file mode 100644 index 0000000000..287f56c34f --- /dev/null +++ b/src/modules/sdlog2/sdlog2_ringbuffer.h @@ -0,0 +1,68 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_ringbuffer.h + * + * Ring FIFO buffer for binary data. + * + * @author Anton Babushkin + */ + +#ifndef SDLOG2_RINGBUFFER_H_ +#define SDLOG2_RINGBUFFER_H_ + +struct sdlog2_logbuffer { + // all pointers are in bytes + int write_ptr; + int read_ptr; + int size; + char *data; +}; + +void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size); + +int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb); + +int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb); + +int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb); + +void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size); + +int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr); + +void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n); + +#endif From 691dc8eefd835c437251e544f74f126bb883869c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 26 May 2013 00:14:10 +0400 Subject: [PATCH 31/89] sdlog2 strick packing fixed, length bug fixed, "sdlog2_dump.py" debug tool added --- Tools/sdlog2_dump.py | 90 ++++++++++++++++++++++++++++++ src/modules/sdlog2/sdlog2.c | 2 + src/modules/sdlog2/sdlog2_format.h | 12 ++-- 3 files changed, 98 insertions(+), 6 deletions(-) create mode 100644 Tools/sdlog2_dump.py diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py new file mode 100644 index 0000000000..bdcbfdda7f --- /dev/null +++ b/Tools/sdlog2_dump.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python + +"""Parse and dump binary log generated by sdlog2 + + Usage: python sdlog2_dump.py """ + +__author__ = "Anton Babushkin" +__version__ = "0.1" + +import struct, sys + +class BufferUnderflow(Exception): + pass + +class SDLog2Parser: + BLOCK_SIZE = 8192 + MSG_HEADER_LEN = 3 + MSG_HEAD1 = 0xA3 + MSG_HEAD2 = 0x95 + MSG_FORMAT_PACKET_LEN = 89 + MSG_TYPE_FORMAT = 0x80 + + def __init__(self): + return + + def reset(self): + self.msg_formats = {} + self.buffer = "" + self.ptr = 0 + + def process(self, fn): + self.reset() + f = open(fn, "r") + while True: + chunk = f.read(self.BLOCK_SIZE) + if len(chunk) == 0: + break + self.buffer = self.buffer[self.ptr:] + chunk + self.ptr = 0 + while self._bytes_left() >= self.MSG_HEADER_LEN: + head1 = ord(self.buffer[self.ptr]) + head2 = ord(self.buffer[self.ptr+1]) + if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): + raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + msg_type = ord(self.buffer[self.ptr+2]) + if msg_type == self.MSG_TYPE_FORMAT: + self._parse_msg_format() + else: + msg_format = self.msg_formats[msg_type] + if msg_format == None: + raise Exception("Unknown msg type: %i" % msg_type) + msg_length = msg_format[0] + if self._bytes_left() < msg_length: + break + self._parse_msg(msg_format) + f.close() + + def _bytes_left(self): + return len(self.buffer) - self.ptr + + def _parse_msg_format(self): + if self._bytes_left() < self.MSG_FORMAT_PACKET_LEN: + raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self._bytes_left(), self.MSG_FORMAT_PACKET_LEN)) + msg_type = ord(self.buffer[self.ptr+3]) + msg_length = ord(self.buffer[self.ptr+4]) + msg_name = self.buffer[self.ptr+5:self.ptr+9].strip('\0') + msg_struct = self.buffer[self.ptr+9:self.ptr+25].strip('\0') + msg_labels = self.buffer[self.ptr+25:self.ptr+89].strip('\0').split(",") + print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s" % (msg_type, msg_length, msg_name, msg_struct, str(msg_labels)) + self.msg_formats[msg_type] = (msg_length, msg_name, msg_struct, msg_labels) + self.ptr += self.MSG_FORMAT_PACKET_LEN + + def _parse_msg(self, msg_format): + msg_length = msg_format[0] + msg_name = msg_format[1] + msg_struct = "<" + msg_format[2] + data = struct.unpack(msg_struct, self.buffer[self.ptr+self.MSG_HEADER_LEN:self.ptr+msg_length]) + print "MSG %s: %s" % (msg_name, str(data)) + self.ptr += msg_format[0] + +def _main(): + if len(sys.argv) < 2: + print "Usage:\npython sdlog2_dump.py " + return + fn = sys.argv[1] + parser = SDLog2Parser() + parser.process(fn) + +if __name__ == "__main__": + _main() diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 38b57082f4..8d4d2f8ced 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -492,6 +492,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } subs; /* log message buffer: header + body */ + #pragma pack(push, 1) struct { LOG_PACKET_HEADER; union { @@ -502,6 +503,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } log_msg = { LOG_PACKET_HEADER_INIT(0) }; + #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); /* --- MANAGEMENT - LOGGING COMMAND --- */ diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h index f5347a7bdd..bbf8b6f12f 100644 --- a/src/modules/sdlog2/sdlog2_format.h +++ b/src/modules/sdlog2/sdlog2_format.h @@ -77,7 +77,7 @@ Format characters in the format string for binary log messages struct log_format_s { uint8_t type; - uint8_t length; + uint8_t length; // full packet length including header char name[4]; char format[16]; char labels[64]; @@ -85,13 +85,13 @@ struct log_format_s { #define LOG_FORMAT(_name, _format, _labels) { \ .type = LOG_##_name##_MSG, \ - .length = sizeof(struct log_##_name##_s) + 8, \ - .name = #_name, \ - .format = _format, \ - .labels = _labels \ + .length = sizeof(struct log_##_name##_s) + LOG_PACKET_HEADER_LEN, \ + .name = #_name, \ + .format = _format, \ + .labels = _labels \ } -#define LOG_FORMAT_MSG 128 +#define LOG_FORMAT_MSG 0x80 #define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) From 1edc36bfd494a3a8bff967592774ce75ca4ce151 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 25 May 2013 23:01:55 +0200 Subject: [PATCH 32/89] More documentation --- src/examples/fixedwing_control/main.c | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 9fd11062a7..89fbef020a 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -33,10 +33,13 @@ ****************************************************************************/ /** * @file main.c - * Implementation of a fixed wing attitude controller. This file is a complete - * fixed wing controller flying manual attitude control or auto waypoint control. + * + * Example implementation of a fixed wing attitude controller. This file is a complete + * fixed wing controller for manual attitude control or auto waypoint control. * There is no need to touch any other system components to extend / modify the * complete control architecture. + * + * @author Lorenz Meier */ #include @@ -60,7 +63,6 @@ #include #include #include -#include #include #include #include @@ -306,7 +308,10 @@ int fixedwing_control_thread_main(int argc, char *argv[]) int ret = poll(fds, 2, 500); if (ret < 0) { - /* poll error, this will not really happen in practice */ + /* + * Poll error, this will not really happen in practice, + * but its good design practice to make output an error message. + */ warnx("poll error"); } else if (ret == 0) { @@ -332,6 +337,8 @@ int fixedwing_control_thread_main(int argc, char *argv[]) orb_check(global_pos_sub, &pos_updated); bool global_sp_updated; orb_check(global_sp_sub, &global_sp_updated); + bool manual_sp_updated; + orb_check(manual_sp_sub, &manual_sp_updated); /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); @@ -357,10 +364,11 @@ int fixedwing_control_thread_main(int argc, char *argv[]) } } - /* get the RC (or otherwise user based) input */ - orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); + if (manual_sp_updated) + /* get the RC (or otherwise user based) input */ + orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); - /* check if the throttle was ever more than 50% - go only to failsafe if yes */ + /* check if the throttle was ever more than 50% - go later only to failsafe if yes */ if (isfinite(manual_sp.throttle) && (manual_sp.throttle >= 0.6f) && (manual_sp.throttle <= 1.0f)) { @@ -372,6 +380,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) /* control */ + /* if in auto mode, fly global position setpoint */ if (vstatus.state_machine == SYSTEM_STATE_AUTO || vstatus.state_machine == SYSTEM_STATE_STABILIZED) { @@ -391,6 +400,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) /* set flaps to zero */ actuators.control[4] = 0.0f; + /* if in manual mode, decide between attitude stabilization (SAS) and full manual pass-through */ } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { From 81e7af31856b0bb5db5dcc8ee90bc98cb6a4cf3d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 26 May 2013 15:35:43 +0400 Subject: [PATCH 33/89] sdlog2_dump.py now supports all fileds formats and able to parse original APM log --- Tools/sdlog2_dump.py | 85 ++++++++++++++++++++++++++++++++------------ 1 file changed, 63 insertions(+), 22 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index bdcbfdda7f..b74bf47396 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -5,7 +5,7 @@ Usage: python sdlog2_dump.py """ __author__ = "Anton Babushkin" -__version__ = "0.1" +__version__ = "0.2" import struct, sys @@ -18,13 +18,34 @@ class SDLog2Parser: MSG_HEAD1 = 0xA3 MSG_HEAD2 = 0x95 MSG_FORMAT_PACKET_LEN = 89 + MSG_FORMAT_STRUCT = "BB4s16s64s" MSG_TYPE_FORMAT = 0x80 + FORMAT_TO_STRUCT = { + "b": ("b", None), + "B": ("B", None), + "h": ("h", None), + "H": ("H", None), + "i": ("i", None), + "I": ("I", None), + "f": ("f", None), + "n": ("4s", None), + "N": ("16s", None), + "Z": ("64s", None), + "c": ("h", 0.01), + "C": ("H", 0.01), + "e": ("i", 0.01), + "E": ("I", 0.01), + "L": ("i", 0.0000001), + "M": ("b", None), + "q": ("q", None), + "Q": ("Q", None), + } def __init__(self): return def reset(self): - self.msg_formats = {} + self.msg_descrs = {} self.buffer = "" self.ptr = 0 @@ -44,39 +65,59 @@ class SDLog2Parser: raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) msg_type = ord(self.buffer[self.ptr+2]) if msg_type == self.MSG_TYPE_FORMAT: - self._parse_msg_format() + self._parse_msg_descr() else: - msg_format = self.msg_formats[msg_type] - if msg_format == None: + msg_descr = self.msg_descrs[msg_type] + if msg_descr == None: raise Exception("Unknown msg type: %i" % msg_type) - msg_length = msg_format[0] + msg_length = msg_descr[0] if self._bytes_left() < msg_length: break - self._parse_msg(msg_format) + self._parse_msg(msg_descr) f.close() def _bytes_left(self): return len(self.buffer) - self.ptr - def _parse_msg_format(self): + def _parse_msg_descr(self): if self._bytes_left() < self.MSG_FORMAT_PACKET_LEN: raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self._bytes_left(), self.MSG_FORMAT_PACKET_LEN)) - msg_type = ord(self.buffer[self.ptr+3]) - msg_length = ord(self.buffer[self.ptr+4]) - msg_name = self.buffer[self.ptr+5:self.ptr+9].strip('\0') - msg_struct = self.buffer[self.ptr+9:self.ptr+25].strip('\0') - msg_labels = self.buffer[self.ptr+25:self.ptr+89].strip('\0').split(",") - print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s" % (msg_type, msg_length, msg_name, msg_struct, str(msg_labels)) - self.msg_formats[msg_type] = (msg_length, msg_name, msg_struct, msg_labels) + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.buffer[self.ptr + 3 : self.ptr + self.MSG_FORMAT_PACKET_LEN]) + msg_type = data[0] + msg_length = data[1] + msg_name = data[2].strip('\0') + msg_format = data[3].strip('\0') + msg_labels = data[4].strip('\0').split(",") + # Convert msg_format to struct.unpack format string + msg_struct = "" + msg_mults = [] + for c in msg_format: + try: + f = self.FORMAT_TO_STRUCT[c] + msg_struct += f[0] + msg_mults.append(f[1]) + except KeyError as e: + raise Exception("Unsupported format char: %s in message %s (0x%02X)" % (c, msg_name, msg_type)) + msg_struct = "<" + msg_struct + print msg_format, msg_struct + print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) + self.msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) self.ptr += self.MSG_FORMAT_PACKET_LEN - def _parse_msg(self, msg_format): - msg_length = msg_format[0] - msg_name = msg_format[1] - msg_struct = "<" + msg_format[2] - data = struct.unpack(msg_struct, self.buffer[self.ptr+self.MSG_HEADER_LEN:self.ptr+msg_length]) - print "MSG %s: %s" % (msg_name, str(data)) - self.ptr += msg_format[0] + def _parse_msg(self, msg_descr): + msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr + data = list(struct.unpack(msg_struct, self.buffer[self.ptr+self.MSG_HEADER_LEN:self.ptr+msg_length])) + s = [] + for i in xrange(len(data)): + if type(data[i]) is str: + data[i] = data[i].strip('\0') + m = msg_mults[i] + if m != None: + data[i] = data[i] * m + s.append(msg_labels[i] + "=" + str(data[i])) + + print "MSG %s: %s" % (msg_name, ", ".join(s)) + self.ptr += msg_length def _main(): if len(sys.argv) < 2: From 73d2baeb20d3c7757c5aca59e6a66bb4d5bb3533 Mon Sep 17 00:00:00 2001 From: marco Date: Sun, 26 May 2013 16:49:33 +0200 Subject: [PATCH 34/89] comments cleaned --- src/drivers/mkblctrl/mkblctrl.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index 4220f552e4..c67276f8af 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -491,8 +491,6 @@ MK::task_main() * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. */ - // loeschen _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : - // loeschen ORB_ID(actuator_controls_0)); _t_actuators = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); /* force a reset of the update rate */ @@ -551,8 +549,7 @@ MK::task_main() _current_update_rate = _update_rate; } - /* sleep waiting for data, stopping to check for PPM - * input at 100Hz */ + /* sleep waiting for data max 100ms */ int ret = ::poll(&fds[0], 2, 100); /* this would be bad... */ @@ -566,7 +563,6 @@ MK::task_main() if (fds[0].revents & POLLIN) { /* get controls - must always do this to avoid spinning */ - // loeschen orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_0), _t_actuators, &_controls); orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls); /* can we mix? */ From f5e405ef5b06f4bf26cf3758d962aa7884a7d94c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 26 May 2013 20:15:46 +0400 Subject: [PATCH 35/89] sdlog2_dump.py now generates customizible CSV output, messages/fields filter added. --- Tools/sdlog2_dump.py | 205 +++++++++++++++++++++++++++++++++---------- 1 file changed, 159 insertions(+), 46 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index b74bf47396..c8fc00a598 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -1,11 +1,21 @@ #!/usr/bin/env python -"""Parse and dump binary log generated by sdlog2 +"""Dump binary log generated by sdlog2 or APM as CSV - Usage: python sdlog2_dump.py """ +Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] + + -v Use plain debug output instead of CSV. + + -d Use "delimiter" in CSV. Default is ",". + + -n Use "null" as placeholder for empty values in CSV. Default is empty. + + -m MSG[.field1,field2,...] + Dump only messages of specified type, and only specified fields. + Multiple -m options allowed.""" __author__ = "Anton Babushkin" -__version__ = "0.2" +__version__ = "1.0" import struct, sys @@ -40,54 +50,83 @@ class SDLog2Parser: "q": ("q", None), "Q": ("Q", None), } + __csv_delim = "," + __csv_null = "" + __msg_filter = {} + __debug_out = False def __init__(self): return def reset(self): - self.msg_descrs = {} - self.buffer = "" - self.ptr = 0 + self.__msg_descrs = {} + self.__buffer = "" + self.__ptr = 0 + self.__csv_columns = [] + self.__csv_data = {} + + def setCSVDelimiter(self, csv_delim): + self.__csv_delim = csv_delim + + def setCSVNull(self, csv_null): + self.__csv_null = csv_null + + def setMsgFilter(self, msg_filter): + self.__msg_filter = msg_filter + + def setDebugOut(self, debug_out): + self.__debug_out = debug_out def process(self, fn): self.reset() + first_data_msg = True f = open(fn, "r") while True: chunk = f.read(self.BLOCK_SIZE) if len(chunk) == 0: break - self.buffer = self.buffer[self.ptr:] + chunk - self.ptr = 0 - while self._bytes_left() >= self.MSG_HEADER_LEN: - head1 = ord(self.buffer[self.ptr]) - head2 = ord(self.buffer[self.ptr+1]) + self.__buffer = self.__buffer[self.__ptr:] + chunk + self.__ptr = 0 + while self.__bytesLeft() >= self.MSG_HEADER_LEN: + head1 = ord(self.__buffer[self.__ptr]) + head2 = ord(self.__buffer[self.__ptr+1]) if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - msg_type = ord(self.buffer[self.ptr+2]) + msg_type = ord(self.__buffer[self.__ptr+2]) if msg_type == self.MSG_TYPE_FORMAT: - self._parse_msg_descr() + self.__parseMsgDescr() else: - msg_descr = self.msg_descrs[msg_type] + msg_descr = self.__msg_descrs[msg_type] if msg_descr == None: raise Exception("Unknown msg type: %i" % msg_type) msg_length = msg_descr[0] - if self._bytes_left() < msg_length: + if self.__bytesLeft() < msg_length: break - self._parse_msg(msg_descr) + if first_data_msg: + print self.__csv_delim.join(self.__csv_columns) + first_data_msg = False + self.__parseMsg(msg_descr) + f.close() - def _bytes_left(self): - return len(self.buffer) - self.ptr + def __bytesLeft(self): + return len(self.__buffer) - self.__ptr - def _parse_msg_descr(self): - if self._bytes_left() < self.MSG_FORMAT_PACKET_LEN: - raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self._bytes_left(), self.MSG_FORMAT_PACKET_LEN)) - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.buffer[self.ptr + 3 : self.ptr + self.MSG_FORMAT_PACKET_LEN]) + def __filterMsg(self, msg_name): + show_fields = "*" + if len(self.__msg_filter) > 0: + show_fields = self.__msg_filter.get(msg_name) + return show_fields + + def __parseMsgDescr(self): + if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: + raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self.__bytesLeft(), self.MSG_FORMAT_PACKET_LEN)) + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] msg_length = data[1] - msg_name = data[2].strip('\0') - msg_format = data[3].strip('\0') - msg_labels = data[4].strip('\0').split(",") + msg_name = data[2].strip("\0") + msg_format = data[3].strip("\0") + msg_labels = data[4].strip("\0").split(",") # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -97,34 +136,108 @@ class SDLog2Parser: msg_struct += f[0] msg_mults.append(f[1]) except KeyError as e: - raise Exception("Unsupported format char: %s in message %s (0x%02X)" % (c, msg_name, msg_type)) - msg_struct = "<" + msg_struct - print msg_format, msg_struct - print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) - self.msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) - self.ptr += self.MSG_FORMAT_PACKET_LEN + raise Exception("Unsupported format char: %s in message %s (%i)" % (c, msg_name, msg_type)) + msg_struct = "<" + msg_struct # force little-endian + self.__msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) + show_fields = self.__filterMsg(msg_name) + if show_fields != None: + if self.__debug_out: + print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( + msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) + else: + if show_fields == "*": + fields = msg_labels + else: + fields = [] + for field in show_fields: + if field in msg_labels: + fields.append(field) + for field in fields: + msg_field = msg_name + "." + field + self.__csv_columns.append(msg_field) + self.__csv_data[msg_field] = None + self.__ptr += self.MSG_FORMAT_PACKET_LEN - def _parse_msg(self, msg_descr): + def __parseMsg(self, msg_descr): msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr - data = list(struct.unpack(msg_struct, self.buffer[self.ptr+self.MSG_HEADER_LEN:self.ptr+msg_length])) - s = [] - for i in xrange(len(data)): - if type(data[i]) is str: - data[i] = data[i].strip('\0') - m = msg_mults[i] - if m != None: - data[i] = data[i] * m - s.append(msg_labels[i] + "=" + str(data[i])) - - print "MSG %s: %s" % (msg_name, ", ".join(s)) - self.ptr += msg_length - + show_fields = self.__filterMsg(msg_name) + if (show_fields != None): + data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + for i in xrange(len(data)): + if type(data[i]) is str: + data[i] = data[i].strip("\0") + m = msg_mults[i] + if m != None: + data[i] = data[i] * m + if self.__debug_out: + s = [] + for i in xrange(len(data)): + label = msg_labels[i] + if show_fields == "*" or label in show_fields: + s.append(label + "=" + str(data[i])) + print "MSG %s: %s" % (msg_name, ", ".join(s)) + else: + # update CSV data buffer + for i in xrange(len(data)): + label = msg_labels[i] + if show_fields == "*" or label in show_fields: + self.__csv_data[msg_name + "." + label] = data[i] + # format and print CSV row + s = [] + for field in self.__csv_columns: + v = self.__csv_data[field] + if v == None: + v = self.__csv_null + else: + v = str(v) + s.append(v) + print self.__csv_delim.join(s) + self.__ptr += msg_length + def _main(): if len(sys.argv) < 2: - print "Usage:\npython sdlog2_dump.py " + print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]]\n" + print "\t-v\tUse plain debug output instead of CSV.\n" + print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" + print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" + print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." return fn = sys.argv[1] + debug_out = False + msg_filter = {} + csv_null = "" + csv_delim = "," + opt = None + for arg in sys.argv[2:]: + if opt != None: + if opt == "d": + csv_delim = arg + elif opt == "n": + csv_null = arg + if opt == "m": + show_fields = "*" + a = arg.split(".") + if len(a) > 1: + show_fields = set(a[1].split(",")) + msg_filter[a[0]] = show_fields + opt = None + else: + if arg == "-v": + debug_out = True + elif arg == "-d": + opt = "d" + elif arg == "-n": + opt = "n" + elif arg == "-m": + opt = "m" + + if csv_delim == "\\t": + csv_delim = "\t" parser = SDLog2Parser() + parser.setCSVDelimiter(csv_delim) + parser.setCSVNull(csv_null) + parser.setMsgFilter(msg_filter) + parser.setDebugOut(debug_out) parser.process(fn) if __name__ == "__main__": From eab01a2efd0c1f1fc9cf32181c63a7e5494f0004 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 26 May 2013 20:51:20 +0200 Subject: [PATCH 36/89] Hotfix: Generate map files for modules as well for more in-depth memory-use debugging. --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index eeba0ff2c6..c75a08bd16 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -219,7 +219,7 @@ endef define PRELINK @$(ECHO) "PRELINK: $1" @$(MKDIR) -p $(dir $1) - $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 + $(Q) $(LD) -Ur -Map $1.map -o $1 $2 && $(OBJCOPY) --localize-hidden $1 endef # Update the archive $1 with the files in $2 From 84aa52c81a248f70171546ee7af317faa067f0ac Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 27 May 2013 18:01:03 +0400 Subject: [PATCH 37/89] sdlog2_dump.py now dumps CSV columns in the same order as args --- Tools/sdlog2_dump.py | 124 ++++++++++++++++++++++++------------------- 1 file changed, 69 insertions(+), 55 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index c8fc00a598..70e7403bc3 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -15,7 +15,7 @@ Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.fi Multiple -m options allowed.""" __author__ = "Anton Babushkin" -__version__ = "1.0" +__version__ = "1.1" import struct, sys @@ -52,18 +52,21 @@ class SDLog2Parser: } __csv_delim = "," __csv_null = "" - __msg_filter = {} + __msg_filter = [] __debug_out = False def __init__(self): return - + def reset(self): - self.__msg_descrs = {} - self.__buffer = "" - self.__ptr = 0 - self.__csv_columns = [] - self.__csv_data = {} + self.__msg_descrs = {} # message descriptions by message type map + self.__msg_labels = {} # message labels by message name map + self.__msg_names = [] # message names in the same order as FORMAT messages + self.__buffer = "" # buffer for input binary data + self.__ptr = 0 # read pointer in buffer + self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" + self.__csv_data = {} # current values for all columns + self.__msg_filter_map = {} # filter in form of map, with '*" expanded to full list of fields def setCSVDelimiter(self, csv_delim): self.__csv_delim = csv_delim @@ -79,6 +82,10 @@ class SDLog2Parser: def process(self, fn): self.reset() + if self.__debug_out: + # init __msg_filter_map + for msg_name, show_fields in self.__msg_filter: + self.__msg_filter_map[msg_name] = show_fields first_data_msg = True f = open(fn, "r") while True: @@ -94,8 +101,10 @@ class SDLog2Parser: raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) msg_type = ord(self.__buffer[self.__ptr+2]) if msg_type == self.MSG_TYPE_FORMAT: + # parse FORMAT message self.__parseMsgDescr() else: + # parse data message msg_descr = self.__msg_descrs[msg_type] if msg_descr == None: raise Exception("Unknown msg type: %i" % msg_type) @@ -103,61 +112,66 @@ class SDLog2Parser: if self.__bytesLeft() < msg_length: break if first_data_msg: - print self.__csv_delim.join(self.__csv_columns) + # build CSV columns and init data map + self.__initCSV() first_data_msg = False self.__parseMsg(msg_descr) - + f.close() - + def __bytesLeft(self): return len(self.__buffer) - self.__ptr - + def __filterMsg(self, msg_name): show_fields = "*" - if len(self.__msg_filter) > 0: - show_fields = self.__msg_filter.get(msg_name) + if len(self.__msg_filter_map) > 0: + show_fields = self.__msg_filter_map.get(msg_name) return show_fields - + + def __initCSV(self): + if len(self.__msg_filter) == 0: + for msg_name in self.__msg_names: + self.__msg_filter.append((msg_name, "*")) + for msg_name, show_fields in self.__msg_filter: + if show_fields == "*": + show_fields = self.__msg_labels.get(msg_name, []) + self.__msg_filter_map[msg_name] = show_fields + for field in show_fields: + full_label = msg_name + "." + field + self.__csv_columns.append(full_label) + self.__csv_data[full_label] = None + print self.__csv_delim.join(self.__csv_columns) + def __parseMsgDescr(self): if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self.__bytesLeft(), self.MSG_FORMAT_PACKET_LEN)) data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] - msg_length = data[1] - msg_name = data[2].strip("\0") - msg_format = data[3].strip("\0") - msg_labels = data[4].strip("\0").split(",") - # Convert msg_format to struct.unpack format string - msg_struct = "" - msg_mults = [] - for c in msg_format: - try: - f = self.FORMAT_TO_STRUCT[c] - msg_struct += f[0] - msg_mults.append(f[1]) - except KeyError as e: - raise Exception("Unsupported format char: %s in message %s (%i)" % (c, msg_name, msg_type)) - msg_struct = "<" + msg_struct # force little-endian - self.__msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) - show_fields = self.__filterMsg(msg_name) - if show_fields != None: + if msg_type != self.MSG_TYPE_FORMAT: + msg_length = data[1] + msg_name = data[2].strip("\0") + msg_format = data[3].strip("\0") + msg_labels = data[4].strip("\0").split(",") + # Convert msg_format to struct.unpack format string + msg_struct = "" + msg_mults = [] + for c in msg_format: + try: + f = self.FORMAT_TO_STRUCT[c] + msg_struct += f[0] + msg_mults.append(f[1]) + except KeyError as e: + raise Exception("Unsupported format char: %s in message %s (%i)" % (c, msg_name, msg_type)) + msg_struct = "<" + msg_struct # force little-endian + self.__msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) + self.__msg_labels[msg_name] = msg_labels + self.__msg_names.append(msg_name) if self.__debug_out: - print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( - msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) - else: - if show_fields == "*": - fields = msg_labels - else: - fields = [] - for field in show_fields: - if field in msg_labels: - fields.append(field) - for field in fields: - msg_field = msg_name + "." + field - self.__csv_columns.append(msg_field) - self.__csv_data[msg_field] = None + if self.__filterMsg(msg_name) != None: + print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( + msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) self.__ptr += self.MSG_FORMAT_PACKET_LEN - + def __parseMsg(self, msg_descr): msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr show_fields = self.__filterMsg(msg_name) @@ -180,12 +194,12 @@ class SDLog2Parser: # update CSV data buffer for i in xrange(len(data)): label = msg_labels[i] - if show_fields == "*" or label in show_fields: + if label in show_fields: self.__csv_data[msg_name + "." + label] = data[i] # format and print CSV row s = [] - for field in self.__csv_columns: - v = self.__csv_data[field] + for full_label in self.__csv_columns: + v = self.__csv_data[full_label] if v == None: v = self.__csv_null else: @@ -204,7 +218,7 @@ def _main(): return fn = sys.argv[1] debug_out = False - msg_filter = {} + msg_filter = [] csv_null = "" csv_delim = "," opt = None @@ -218,8 +232,8 @@ def _main(): show_fields = "*" a = arg.split(".") if len(a) > 1: - show_fields = set(a[1].split(",")) - msg_filter[a[0]] = show_fields + show_fields = a[1].split(",") + msg_filter.append((a[0], show_fields)) opt = None else: if arg == "-v": @@ -230,7 +244,7 @@ def _main(): opt = "n" elif arg == "-m": opt = "m" - + if csv_delim == "\\t": csv_delim = "\t" parser = SDLog2Parser() From 8dbda512897b3d2a05d39ebc26aba35b86ce044d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 27 May 2013 18:04:19 +0400 Subject: [PATCH 38/89] Cleanup --- Tools/sdlog2_dump.py | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 70e7403bc3..fa02a37237 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -19,9 +19,6 @@ __version__ = "1.1" import struct, sys -class BufferUnderflow(Exception): - pass - class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -102,6 +99,8 @@ class SDLog2Parser: msg_type = ord(self.__buffer[self.__ptr+2]) if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message + if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: + break self.__parseMsgDescr() else: # parse data message @@ -143,8 +142,6 @@ class SDLog2Parser: print self.__csv_delim.join(self.__csv_columns) def __parseMsgDescr(self): - if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: - raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self.__bytesLeft(), self.MSG_FORMAT_PACKET_LEN)) data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] if msg_type != self.MSG_TYPE_FORMAT: From f1a8f6e75b98768daa5bc5290ccf60156d8185da Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 27 May 2013 16:58:03 +0200 Subject: [PATCH 39/89] Hotfix: Made HMC driver more verbose to prevent false alarm --- src/drivers/hmc5883/hmc5883.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 78eda327c3..7de394f244 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1224,10 +1224,12 @@ start() errx(1, "already started"); /* create the driver, attempt expansion bus first */ + warnx("probing for external sensor.."); g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION); if (g_dev != nullptr && OK != g_dev->init()) { delete g_dev; g_dev = nullptr; + warnx("no external sensor, using internal.."); } From 27ee36b2049167a1272122548fe61aa2993d79c1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 28 May 2013 07:18:07 +0200 Subject: [PATCH 40/89] Hotfix: Completely silencing HMC5883 probing to not confuse users --- src/drivers/hmc5883/hmc5883.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 7de394f244..59e90d86c1 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -329,7 +329,7 @@ HMC5883::HMC5883(int bus) : _calibrated(false) { // enable debug() calls - _debug_enabled = true; + _debug_enabled = false; // default scaling _scale.x_offset = 0; @@ -1224,12 +1224,10 @@ start() errx(1, "already started"); /* create the driver, attempt expansion bus first */ - warnx("probing for external sensor.."); g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION); if (g_dev != nullptr && OK != g_dev->init()) { delete g_dev; g_dev = nullptr; - warnx("no external sensor, using internal.."); } From f336a86baa6e0a9ef0b7bbb82e7f3ea4847d15dc Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:29:31 +1000 Subject: [PATCH 41/89] I finished to implement nonlinear complementary filter on the SO(3). The previous problem was roll,pitch and yaw angle from quaternion. Now it is fixed. 1-2-3 Euler representation is used. Also accelerometer sign change has been applied. --- .../attitude_estimator_so3_comp_main.cpp | 172 ++++++++++++------ 1 file changed, 118 insertions(+), 54 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 28fcf03692..9bb749cafb 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_main.c * - * Nonlinear SO3 filter for Attitude Estimation. + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include @@ -46,7 +58,13 @@ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ -static float gravity_vector[3] = {0.0f,0.0f,0.0f}; /** estimated gravity vector */ +static bool bFilterInit = false; + +//! Auxiliary variables to reduce number of repeated operations +static float q0q0, q0q1, q0q2, q0q3; +static float q1q1, q1q2, q1q3; +static float q2q2, q2q3; +static float q3q3; //! Serial packet related static int uart; @@ -150,29 +168,77 @@ float invSqrt(float number) { return y; } +//! Using accelerometer, sense the gravity vector. +//! Using magnetometer, sense yaw. +void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) +{ + float initialRoll, initialPitch; + float cosRoll, sinRoll, cosPitch, sinPitch; + float magX, magY; + float initialHdg, cosHeading, sinHeading; + + initialRoll = atan2(-ay, -az); + initialPitch = atan2(ax, -az); + + cosRoll = cosf(initialRoll); + sinRoll = sinf(initialRoll); + cosPitch = cosf(initialPitch); + sinPitch = sinf(initialPitch); + + magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch; + + magY = my * cosRoll - mz * sinRoll; + + initialHdg = atan2f(-magY, magX); + + cosRoll = cosf(initialRoll * 0.5f); + sinRoll = sinf(initialRoll * 0.5f); + + cosPitch = cosf(initialPitch * 0.5f); + sinPitch = sinf(initialPitch * 0.5f); + + cosHeading = cosf(initialHdg * 0.5f); + sinHeading = sinf(initialHdg * 0.5f); + + q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading; + q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading; + q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading; + q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading; + + // auxillary variables to reduce number of repeated operations, for 1st pass + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; +} + void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; + //! Make filter converge to initial solution faster + //! This function assumes you are in static position. + //! WARNING : in case air reboot, this can cause problem. But this is very + //! unlikely happen. + if(bFilterInit == false) + { + MahonyAHRSinit(ax,ay,az,mx,my,mz); + bFilterInit = true; + } + //! If magnetometer measurement is available, use it. if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - float hx, hy, bx, bz; + float hx, hy, hz, bx, bz; float halfwx, halfwy, halfwz; // Normalise magnetometer measurement + // Will sqrt work better? PX4 system is powerful enough? recipNorm = invSqrt(mx * mx + my * my + mz * mz); mx *= recipNorm; my *= recipNorm; @@ -181,8 +247,9 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Reference direction of Earth's magnetic field hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5 - q1q1 - q2q2); bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + bz = hz; // Estimated direction of magnetic field halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); @@ -203,7 +270,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az recipNorm = invSqrt(ax * ax + ay * ay + az * az); ax *= recipNorm; ay *= recipNorm; - az *= recipNorm; + az *= recipNorm; // Estimated direction of gravity and magnetic field halfvx = q1q3 - q0q2; @@ -254,6 +321,18 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az q1 *= recipNorm; q2 *= recipNorm; q3 *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; } void send_uart_byte(char c) @@ -630,44 +709,29 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds uint64_t timing_start = hrt_absolute_time(); - MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + // NOTE : Accelerometer is reversed. + // Because proper mount of PX4 will give you a reversed accelerometer readings. + MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); - float aSq = q0*q0; // 1 - float bSq = q1*q1; // 2 - float cSq = q2*q2; // 3 - float dSq = q3*q3; // 4 - float a = q0; - float b = q1; - float c = q2; - float d = q3; - - Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11 - //Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 - //Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 - Rot_matrix[3] = 2.0 * (b * c - a * d); // 21 - //Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 - //Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 - Rot_matrix[6] = 2.0 * (b * d + a * c); // 31 - Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 - Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 - - gravity_vector[0] = 2*(q1*q3-q0*q2); - gravity_vector[1] = 2*(q0*q1+q2*q3); - gravity_vector[2] = aSq - bSq - cSq + dSq; - - //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - //euler[1] = -asinf(Rot_matrix[6]); - //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); - - // Euler angle directly from quaternion. - euler[0] = -atan2f(gravity_vector[1], sqrtf(gravity_vector[0]*gravity_vector[0] + gravity_vector[2]*gravity_vector[2])); // roll - euler[1] = atan2f(gravity_vector[0], sqrtf(gravity_vector[1]*gravity_vector[1] + gravity_vector[2]*gravity_vector[2])); // pitch - euler[2] = -atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); // yaw - - //euler[2] = atan2(2 * q1*q2 - 2 * q0*q3, 2 * q0*q0 + 2 * q1*q1 - 1); // psi - //euler[1] = -asin(2 * q1*q3 + 2 * q0*q2); // theta - //euler[0] = atan2(2 * q2*q3 - 2 * q0*q1, 2 * q0*q0 + 2 * q3*q3 - 1); // phi + // Convert q->R. + Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11 + Rot_matrix[1] = 2.0 * (q1*q2 + q0*q3); // 12 + Rot_matrix[2] = 2.0 * (q1*q3 - q0*q2); // 13 + Rot_matrix[3] = 2.0 * (q1*q2 - q0*q3); // 21 + Rot_matrix[4] = q0q0 - q1q1 + q2q2 - q3q3;// 22 + Rot_matrix[5] = 2.0 * (q2*q3 + q0*q1); // 23 + Rot_matrix[6] = 2.0 * (q1*q3 + q0*q2); // 31 + Rot_matrix[7] = 2.0 * (q2*q3 - q0*q1); // 32 + Rot_matrix[8] = q0q0 - q1q1 - q2q2 + q3q3;// 33 + //1-2-3 Representation. + //Equation (290) + //Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors, James Diebel. + // Existing PX4 EKF code was generated by MATLAB which uses coloum major order matrix. + euler[0] = atan2f(Rot_matrix[5], Rot_matrix[8]); //! Roll + euler[1] = -asinf(Rot_matrix[2]); //! Pitch + euler[2] = atan2f(Rot_matrix[1],Rot_matrix[0]); //! Yaw + /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { /* Do something */ From cc6c590af062d80681430fa5139837c87fbd72f0 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:29:31 +1000 Subject: [PATCH 42/89] I finished to implement nonlinear complementary filter on the SO(3). The previous problem was roll,pitch and yaw angle from quaternion. Now it is fixed. 1-2-3 Euler representation is used. Also accelerometer sign change has been applied. --- .../attitude_estimator_so3_comp_main.cpp | 172 ++++++++++++------ 1 file changed, 118 insertions(+), 54 deletions(-) diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 28fcf03692..9bb749cafb 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_main.c * - * Nonlinear SO3 filter for Attitude Estimation. + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include @@ -46,7 +58,13 @@ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ -static float gravity_vector[3] = {0.0f,0.0f,0.0f}; /** estimated gravity vector */ +static bool bFilterInit = false; + +//! Auxiliary variables to reduce number of repeated operations +static float q0q0, q0q1, q0q2, q0q3; +static float q1q1, q1q2, q1q3; +static float q2q2, q2q3; +static float q3q3; //! Serial packet related static int uart; @@ -150,29 +168,77 @@ float invSqrt(float number) { return y; } +//! Using accelerometer, sense the gravity vector. +//! Using magnetometer, sense yaw. +void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) +{ + float initialRoll, initialPitch; + float cosRoll, sinRoll, cosPitch, sinPitch; + float magX, magY; + float initialHdg, cosHeading, sinHeading; + + initialRoll = atan2(-ay, -az); + initialPitch = atan2(ax, -az); + + cosRoll = cosf(initialRoll); + sinRoll = sinf(initialRoll); + cosPitch = cosf(initialPitch); + sinPitch = sinf(initialPitch); + + magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch; + + magY = my * cosRoll - mz * sinRoll; + + initialHdg = atan2f(-magY, magX); + + cosRoll = cosf(initialRoll * 0.5f); + sinRoll = sinf(initialRoll * 0.5f); + + cosPitch = cosf(initialPitch * 0.5f); + sinPitch = sinf(initialPitch * 0.5f); + + cosHeading = cosf(initialHdg * 0.5f); + sinHeading = sinf(initialHdg * 0.5f); + + q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading; + q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading; + q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading; + q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading; + + // auxillary variables to reduce number of repeated operations, for 1st pass + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; +} + void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; + //! Make filter converge to initial solution faster + //! This function assumes you are in static position. + //! WARNING : in case air reboot, this can cause problem. But this is very + //! unlikely happen. + if(bFilterInit == false) + { + MahonyAHRSinit(ax,ay,az,mx,my,mz); + bFilterInit = true; + } + //! If magnetometer measurement is available, use it. if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - float hx, hy, bx, bz; + float hx, hy, hz, bx, bz; float halfwx, halfwy, halfwz; // Normalise magnetometer measurement + // Will sqrt work better? PX4 system is powerful enough? recipNorm = invSqrt(mx * mx + my * my + mz * mz); mx *= recipNorm; my *= recipNorm; @@ -181,8 +247,9 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Reference direction of Earth's magnetic field hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5 - q1q1 - q2q2); bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + bz = hz; // Estimated direction of magnetic field halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); @@ -203,7 +270,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az recipNorm = invSqrt(ax * ax + ay * ay + az * az); ax *= recipNorm; ay *= recipNorm; - az *= recipNorm; + az *= recipNorm; // Estimated direction of gravity and magnetic field halfvx = q1q3 - q0q2; @@ -254,6 +321,18 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az q1 *= recipNorm; q2 *= recipNorm; q3 *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; } void send_uart_byte(char c) @@ -630,44 +709,29 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds uint64_t timing_start = hrt_absolute_time(); - MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + // NOTE : Accelerometer is reversed. + // Because proper mount of PX4 will give you a reversed accelerometer readings. + MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); - float aSq = q0*q0; // 1 - float bSq = q1*q1; // 2 - float cSq = q2*q2; // 3 - float dSq = q3*q3; // 4 - float a = q0; - float b = q1; - float c = q2; - float d = q3; - - Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11 - //Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 - //Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 - Rot_matrix[3] = 2.0 * (b * c - a * d); // 21 - //Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 - //Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 - Rot_matrix[6] = 2.0 * (b * d + a * c); // 31 - Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 - Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 - - gravity_vector[0] = 2*(q1*q3-q0*q2); - gravity_vector[1] = 2*(q0*q1+q2*q3); - gravity_vector[2] = aSq - bSq - cSq + dSq; - - //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - //euler[1] = -asinf(Rot_matrix[6]); - //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); - - // Euler angle directly from quaternion. - euler[0] = -atan2f(gravity_vector[1], sqrtf(gravity_vector[0]*gravity_vector[0] + gravity_vector[2]*gravity_vector[2])); // roll - euler[1] = atan2f(gravity_vector[0], sqrtf(gravity_vector[1]*gravity_vector[1] + gravity_vector[2]*gravity_vector[2])); // pitch - euler[2] = -atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); // yaw - - //euler[2] = atan2(2 * q1*q2 - 2 * q0*q3, 2 * q0*q0 + 2 * q1*q1 - 1); // psi - //euler[1] = -asin(2 * q1*q3 + 2 * q0*q2); // theta - //euler[0] = atan2(2 * q2*q3 - 2 * q0*q1, 2 * q0*q0 + 2 * q3*q3 - 1); // phi + // Convert q->R. + Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11 + Rot_matrix[1] = 2.0 * (q1*q2 + q0*q3); // 12 + Rot_matrix[2] = 2.0 * (q1*q3 - q0*q2); // 13 + Rot_matrix[3] = 2.0 * (q1*q2 - q0*q3); // 21 + Rot_matrix[4] = q0q0 - q1q1 + q2q2 - q3q3;// 22 + Rot_matrix[5] = 2.0 * (q2*q3 + q0*q1); // 23 + Rot_matrix[6] = 2.0 * (q1*q3 + q0*q2); // 31 + Rot_matrix[7] = 2.0 * (q2*q3 - q0*q1); // 32 + Rot_matrix[8] = q0q0 - q1q1 - q2q2 + q3q3;// 33 + //1-2-3 Representation. + //Equation (290) + //Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors, James Diebel. + // Existing PX4 EKF code was generated by MATLAB which uses coloum major order matrix. + euler[0] = atan2f(Rot_matrix[5], Rot_matrix[8]); //! Roll + euler[1] = -asinf(Rot_matrix[2]); //! Pitch + euler[2] = atan2f(Rot_matrix[1],Rot_matrix[0]); //! Yaw + /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { /* Do something */ From 7a2adb22eb3ebec5fd90d1d4fbce3f5dbd61bb3c Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:45:02 +1000 Subject: [PATCH 43/89] Visualization code has been added. --- .../attitude_estimator_so3_comp/README | 5 + .../attitude_estimator_so3_comp_params.c | 14 +- .../attitude_estimator_so3_comp_params.h | 14 +- .../FreeIMU_cube/FreeIMU_cube.pde | 265 +++++++ .../FreeIMU_cube/LICENSE.txt | 674 ++++++++++++++++++ .../FreeIMU_cube/data/CourierNew36.vlw | Bin 0 -> 114920 bytes .../FreeIMU_yaw_pitch_roll.pde | 229 ++++++ .../FreeIMU_yaw_pitch_roll/LICENSE.txt | 674 ++++++++++++++++++ .../data/CourierNew36.vlw | Bin 0 -> 114920 bytes .../visualization_code/README | 9 + 10 files changed, 1882 insertions(+), 2 deletions(-) create mode 100644 src/modules/attitude_estimator_so3_comp/README create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/README diff --git a/src/modules/attitude_estimator_so3_comp/README b/src/modules/attitude_estimator_so3_comp/README new file mode 100644 index 0000000000..26b270d37c --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/README @@ -0,0 +1,5 @@ +Synopsis + + nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 + +Option -d is for debugging packet. See visualization_code folder. diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 068e4340a6..1d5e0670a0 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_params.c * - * Parameters for SO3 complementary filter + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include "attitude_estimator_so3_comp_params.h" diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h index 2fccec61ce..f006956308 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_params.h * - * Parameters for EKF filter + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde new file mode 100644 index 0000000000..3706437d33 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde @@ -0,0 +1,265 @@ +/** +Visualize a cube which will assumes the orientation described +in a quaternion coming from the serial port. + +INSTRUCTIONS: +This program has to be run when you have the FreeIMU_serial +program running on your Arduino and the Arduino connected to your PC. +Remember to set the serialPort variable below to point to the name the +Arduino serial port has in your system. You can get the port using the +Arduino IDE from Tools->Serial Port: the selected entry is what you have +to use as serialPort variable. + + +Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ + +This program is free software: you can redistribute it and/or modify +it under the terms of the version 3 GNU General Public License as +published by the Free Software Foundation. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see . + +*/ + +import processing.serial.*; +import processing.opengl.*; + +Serial myPort; // Create object from Serial class + +final String serialPort = "/dev/ttyUSB9"; // replace this with your serial port. On windows you will need something like "COM1". + +float [] q = new float [4]; +float [] hq = null; +float [] Euler = new float [3]; // psi, theta, phi + +int lf = 10; // 10 is '\n' in ASCII +byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) + +PFont font; +final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; + +final int burst = 32; +int count = 0; + +void myDelay(int time) { + try { + Thread.sleep(time); + } catch (InterruptedException e) { } +} + +void setup() +{ + size(VIEW_SIZE_X, VIEW_SIZE_Y, OPENGL); + myPort = new Serial(this, serialPort, 115200); + + // The font must be located in the sketch's "data" directory to load successfully + font = loadFont("CourierNew36.vlw"); + + println("Waiting IMU.."); + + myPort.clear(); + + while (myPort.available() == 0) { + myPort.write("v"); + myDelay(1000); + } + println(myPort.readStringUntil('\n')); + myPort.write("q" + char(burst)); + myPort.bufferUntil('\n'); +} + + +float decodeFloat(String inString) { + byte [] inData = new byte[4]; + + if(inString.length() == 8) { + inData[0] = (byte) unhex(inString.substring(0, 2)); + inData[1] = (byte) unhex(inString.substring(2, 4)); + inData[2] = (byte) unhex(inString.substring(4, 6)); + inData[3] = (byte) unhex(inString.substring(6, 8)); + } + + int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); + return Float.intBitsToFloat(intbits); +} + +void serialEvent(Serial p) { + if(p.available() >= 18) { + String inputString = p.readStringUntil('\n'); + //print(inputString); + if (inputString != null && inputString.length() > 0) { + String [] inputStringArr = split(inputString, ","); + if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements + q[0] = decodeFloat(inputStringArr[0]); + q[1] = decodeFloat(inputStringArr[1]); + q[2] = decodeFloat(inputStringArr[2]); + q[3] = decodeFloat(inputStringArr[3]); + } + } + count = count + 1; + if(burst == count) { // ask more data when burst completed + p.write("q" + char(burst)); + count = 0; + } + } +} + + + +void buildBoxShape() { + //box(60, 10, 40); + noStroke(); + beginShape(QUADS); + + //Z+ (to the drawing area) + fill(#00ff00); + vertex(-30, -5, 20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + //Z- + fill(#0000ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, 5, -20); + vertex(-30, 5, -20); + + //X- + fill(#ff0000); + vertex(-30, -5, -20); + vertex(-30, -5, 20); + vertex(-30, 5, 20); + vertex(-30, 5, -20); + + //X+ + fill(#ffff00); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(30, 5, -20); + + //Y- + fill(#ff00ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(-30, -5, 20); + + //Y+ + fill(#00ffff); + vertex(-30, 5, -20); + vertex(30, 5, -20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + endShape(); +} + + +void drawCube() { + pushMatrix(); + translate(VIEW_SIZE_X/2, VIEW_SIZE_Y/2 + 50, 0); + scale(5,5,5); + + // a demonstration of the following is at + // http://www.varesano.net/blog/fabio/ahrs-sensor-fusion-orientation-filter-3d-graphical-rotating-cube + rotateZ(-Euler[2]); + rotateX(-Euler[1]); + rotateY(-Euler[0]); + + buildBoxShape(); + + popMatrix(); +} + + +void draw() { + background(#000000); + fill(#ffffff); + + if(hq != null) { // use home quaternion + quaternionToEuler(quatProd(hq, q), Euler); + text("Disable home position by pressing \"n\"", 20, VIEW_SIZE_Y - 30); + } + else { + quaternionToEuler(q, Euler); + text("Point FreeIMU's X axis to your monitor then press \"h\"", 20, VIEW_SIZE_Y - 30); + } + + textFont(font, 20); + textAlign(LEFT, TOP); + text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 20); + text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 20); + + drawCube(); + //myPort.write("q" + 1); +} + + +void keyPressed() { + if(key == 'h') { + println("pressed h"); + + // set hq the home quaternion as the quatnion conjugate coming from the sensor fusion + hq = quatConjugate(q); + + } + else if(key == 'n') { + println("pressed n"); + hq = null; + } +} + +// See Sebastian O.H. Madwick report +// "An efficient orientation filter for inertial and intertial/magnetic sensor arrays" Chapter 2 Quaternion representation + +void quaternionToEuler(float [] q, float [] euler) { + euler[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); // psi + euler[1] = -asin(2 * q[1] * q[3] + 2 * q[0] * q[2]); // theta + euler[2] = atan2(2 * q[2] * q[3] - 2 * q[0] * q[1], 2 * q[0] * q[0] + 2 * q[3] * q[3] - 1); // phi +} + +float [] quatProd(float [] a, float [] b) { + float [] q = new float[4]; + + q[0] = a[0] * b[0] - a[1] * b[1] - a[2] * b[2] - a[3] * b[3]; + q[1] = a[0] * b[1] + a[1] * b[0] + a[2] * b[3] - a[3] * b[2]; + q[2] = a[0] * b[2] - a[1] * b[3] + a[2] * b[0] + a[3] * b[1]; + q[3] = a[0] * b[3] + a[1] * b[2] - a[2] * b[1] + a[3] * b[0]; + + return q; +} + +// returns a quaternion from an axis angle representation +float [] quatAxisAngle(float [] axis, float angle) { + float [] q = new float[4]; + + float halfAngle = angle / 2.0; + float sinHalfAngle = sin(halfAngle); + q[0] = cos(halfAngle); + q[1] = -axis[0] * sinHalfAngle; + q[2] = -axis[1] * sinHalfAngle; + q[3] = -axis[2] * sinHalfAngle; + + return q; +} + +// return the quaternion conjugate of quat +float [] quatConjugate(float [] quat) { + float [] conj = new float[4]; + + conj[0] = quat[0]; + conj[1] = -quat[1]; + conj[2] = -quat[2]; + conj[3] = -quat[3]; + + return conj; +} + diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt new file mode 100644 index 0000000000..94a9ed024d --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw new file mode 100644 index 0000000000000000000000000000000000000000..904771486a1a6d241fb5184282eb99780f730615 GIT binary patch literal 114920 zcmeFa4{%l6_aAiL{l%ElG%aF^6jR<0`9(}4QW23KrYS8_M8uR9DMiYU(niFXrV*tS zX@}7hD*SK3{~yKw@5le&iT_`>{z~f- z&vb;%`2XGb|6TYez83#~2mT3vAO1Jse=YtQNB^(kpTIim@bAZE7y4A(XVm! z@c-Rj9Q|76-w!|A!mzeQ+qo6EjreDnar|F{f5Jb2|8!i1!~{VD+~0@)-;00Er}h0I z;MhiO=iddtwzCm_wnghBO-M_^KZt*p!E#w=*HV+&^N&ewmtYr;RID=09rV{B|m>ca@3L zKKx@V#O*FqpO*QXh+|z!Px_Ufd*CPkDDN_kJWlw>@lRgnKl@Erp$Q)5(KymT;g7(x zT)t)-r!-?a?cX1T|L?&+c|mEdaeIMdTEigq1ZXI0h!*}o#_TiuT z*nf?KSKyz(FXMFF>DPSwZJeJ^l%zH7dJ+QyZm=V2Si@}x|U*8hx+E7$iH8&|HrKZ!Wb)pGfc*nF-&gcbf2 zJnVzcBl?vm{aT~{Y z$p=^A&%#5z-v=Fs6Tq`B%0=emKj#(UpTqxhvhF0}()o1W{yD^P4k<5jjFo1mtY7+$ zaV_9q`~F*qV;R~O=2Lln8h*+Kr8WK9hd&QL+pTn=U*QZq%jNqEh)d_wGXG+kd^(R> zZ9biwEJOSE&%@8Tpl$KndDiCBIOfwb{{tjFrPu{xv~A1Z5-=izv(Ki&s&`4 zW4xC6uh_Io7v@u1|Eo66_1%*%7i^r)Bj!{1EATMv$7z`tfoFN;%KWP~AM>XBa0xih zBkDnn-j!_N#N|%2fezuwaEb{>R{y)GaJitHO z&-xk1_UbzQZ@~WtERJ!Uzd8;N;U`UW9O&2j{!RGFf69Ywlg2%QpJ|nzbQS(Bc$VvX zAL3ZQ*2nhfIQ-l2vt6VU@%*RWLHKv@uXPdc*Y_A<>WaGdlMb5i--Vwv^y#Vf^#jj* zTJG=mcqyeLR^~G zTHgTT*iPjown^#v*Wv$z_~)9zw){blW`irl{U_^9pgZh~qrbeDrI+{{?=| zf1O9a&znbc!29(vo#y*r;ZOHZ`#!%y-2b*h+ydhK`smj(|96{Dd7gDEzx*F7#4WB6 z_kSXeb!eINYnlI-jZ>O2PWzsPpY`jw`(yimuMn48A@2V{9P7|B{rd7N#QndBV;gm? zqF-rNuyI-@(`X<5Kls^hon!QCzHo)O-(DfEh&Z-e%cNh+{9EvUkAKc(;x~AF#{EC# zyvF_hIPN>PcbPTdJC4;deEl8eA=h;Nvp#Qq_>Su==d-rcG>UXlI8OKo)z*@{xP4ng?!V-$_nS6O^D$2I zHNo$kKwb*>xPL`qc{F64Hjsxq~`i{WQ{;4eYdE!q2PugpoC+ENW)4(U%iLiz5j>5BC z|Nac(mdkg1g?xY3=2Jdp89GKMY(BP?G-KTw_vhdzuW3H^RpV$6VS3F+SL1#Qe%7J+ z{Q6D<&pI@pU*DexeiQzcKUtsB`iza!abVqA-(P^Ab!a~NHQ!%^pK?yemVV9G4nJj` z#?i0i{+HnA*l8U78rK0o>(Ds*HSRCN&pv4!{TlaI;3qxVFSeh43*TLYhvoP*(?0xF z;8{*Nnq2~(?bdwsYd-G7*>258zxMqy{L9t%*ATZ{eYX+k^91{0>&tMDKzUBtOg!tO z><47HM_4Xy0&z^I`8Yj_t4gb@)kVk&ho_fTvyl*okw(a{QBW1o&0e}knrp51NlgGsrAsM{x)N9yvh7*n~ppEwhx=h zW9c$Aj&0^R`SocW+r>C7lVxZe$DQrbxL=3g_F*%}kG!L0vJTDnhv5GW{Ie{!k!dY# z=DNvoQMpT3%ls|)ec9^wk20A&p=JJoSjXJ_7j2xjh3&R&`3>&-nNN9;e#@V~%`~h- z%cS4JZ!4{}Ocz((TgdfP-)Hp?Xta+CA%F98{QdBPzt0}?_u)PM_H^*~)G_`ZImF-n z4gB3u$=^(X%()<#h@y8vaA;xSpf@2YKe<@B4_d4!_T$r|{tS zVe|kV{N9Xi!GqsZ(Mfpl+Y+_FgWr7-xf8$D5r-eYnIhbPzpv>D2IMzrFK{_%D|DM+ z5G=6?!CWNC;mb&y%&(-Wjw0;X%&#E!MA1+Xm|sDF22apc`4z-*5HbkNuOQAwY`Xak zg7*2a2=ZpL=zk%cJ4-tF5C&~Rdd1DPv5+@Wv`2n-Ns(-M1hHp+1r)1ECAx0UqOL04h4bv6~s^!HGt|- zwAE(Gk}Cr9E2u)0hg*ndZGzxp*a2@xcuo;?FN9zb9}JIp7&P7sZSN)3=I>ehRQ9^Q zMN7w#P8eBnb3uSkg;yFfLG9UDU@`vhz|W?}FS3<$+6RQgqKD=;=lm zPv_rJfElPjH_&kzKEbR*3S^tmB$>V_y34{BuI{f4GWBhknprVi5@{fRAXrd8-LV~D z*TVJs&i+M&W*_d?+Ta4=g?<#GWaKUsys|+B3D*>JD9WF$sA$bcnr0vp zMrn-(ZIVJ%L0^UN6@4WLo8_#_aySalRaBfSxI%+#uG)hcpx%f1NK3V)9z3wlky%X(sTJ{UHpS@aZUeyE)i1HrHl( zdqAdoP`Sot0Nqo(0b<#-Hp!SsElm&iMifyb$FLO@`k39w5=Ak;oUmf6Bfx@FoIkrA z;kUt>5FLt6;kd#5j^apW3U|66w%1msMdHnt;R*rR$(a{^k zG(ud(5H7R@J11S3a{{YI=0x9QJ}ON1ZreH^6|S1a%Pd$oWRWrpQ*~6sWytXA=J)wl zHU)j647`MrFy$p5%`jR6N#Of49(Ds_(yhZRb+$(UOz~$&o!=+>) zW5VGC6<5O=uj$E-mywRt;>cz=^-+Fs9qtXdb;!y3vDS+C57vVkY+rB@2(;I=KiKp> zd*)2;{U+cj9mhBiUn5Z$+^y(FVIw>&mm{*4-6Y|OxDIy{+>9Hkgi9`@ zy4*UZ#(@&qh=NV*$^6)rts*(Mc8z6E3Uh%4qEY-u*$MtS z_)!0ZBWIxa1ahY4)PRHr&(xUW$l6iVZ)6dYdM&hQ8#I|3#dWf1b} zH5_y~%iz)M2vx<}k=#iJ1+IinIWh>dT-#VWD9j6eF5(in!h_s}xc3GfUcktBkXKm% z+!t(zEvlrqT^>EQuo+K-pc763oHPKp3ycL$pMr=viQr+B0}1pTPDL1n7(VJ#Lek!7 zRwU(IM12Gz;e|LdVUhDkL&Hcovh^*JzayzaDhVTv#F^skZ{s|fI)+znbrjq-C)Q08 z2>*j|;$U|wdRWv?mjDy)r3=6VX5Qw7q5D4ef|<#vNJ1!_gGQo$xRtX}NI9VZDRWKz zaH|)ioGLR!Uoq2FQ`F|7g=!7Jz3D4MBFttgz3AR3q6Ai`$BM0fx=*6$s2ARD=Z&H; zarUbpE<~v6AcDo9?DC>9@Xx$pfanH4oEJ8UF_-5P(Gs!!-gFpF-&5*dRW310q*Ypo zJdfnfaG&qWWOh7;2lM}Z6x}z)-{*b|%_W->s%9Z^K?@@^fVdDvz2jybkOU1;G!7}^ zR&R)0PD6>49|S%&oGuT7&+#ml{r6~((_Jad-=D^Qw*RE%nR>_!0~6Rz1i_9)4P*7$gLypz zmf{X#0_$iBf%NwBw(VBLUGF_7&2%N9m7z}7ED_6y9s)eKRX-1 z^0B&)$;khMBhjrxdSLY0n`r?kX{#s^)iQhhqHw+`{DvsK)^Zn(m4c0(3Q?mq`!XDbqR}H-wsEVCrsyGo$$CL}?_x1Ox46`E zP=;;Iz7Eoy3RD8xg4Udm_;3(et4}<5y@XyA=AYl%=a)(qG?odQL~6Kr5+#m3h|PT* zgoK-`iGy8Sh+J@UflGx8zKn8MFf|BM97oy)t7na>XM@*`=5Avfigsx=v2S!ekl-md zViFWl2%mwp08qSfjR25-0^#}_w@Og9jC(d-i?BhA1_4DGkNg%Fxk7meGprt>ICsvZ zu*FyhDLw(Q{nmI`n0#PI)T?C>^iH;8b~6x5NHTP4Lr{4NvT6*Rdva;4+0?rM3>|CL z#GOrZGPW-%j!e(1lBu^J`_t1)Mxe6HYOw5OFj;uLsS^95ZRa3L7uUV?T8_B=LCt*% zHw)vUqipKzpUM}*?3;TBSdfK=?tyHWAMG}BuHl*H;l>lvR)b=$rDQ2SICZ^`&cO8VZJs#MT3AyVXSm3vt<5)%H49$o3y0;scmkMZ()U*`2w{qxsE- zB?{eJf(;iiJI6C@+N{x%wr8X0EXHGrBSdJAqE}B~vo;}Ys6cl}j9C1FM!T(&&NNW- zv#?+nWZ6O(ZF?MGmSrzCLTDZyKvhjNNyl)P*>1bA-9c@;HIgsp-`=Q4q>KCU9+oMv z4a)dk&k)$-t&2!dU5J)2_zpVEuHA(pLY18wU$O4!Fc60Zygdmd(Ewz-DF#_r4B=-qMbrfZMAgZH@DpWrd@2&1&90hnT;)q<&FcqG=C!qtXMrlA{EMa|GY zmn{ELaq7c=s}k-E<~Zhag@$1RE`X3u`QS?T#MoRU$sMe7O(^tL3ufG!!!P08E5;qy zfLln{i6RVS4N=#1Jk1u13;peu5bG`v=Zo2=tvUjGb%pp~8oHAWH;`{effbNN3!UqO z%3~vFFy=4>;Jg`a8l|5G0a|j}cA^T2chCmogaT6E4bV-S0NZTv63-E=ren1IN_3Q4 zAHp6AxwROHtZk4Owb#%bl)F$HY`h{3gvDk(DvKe9thFy}c<#Kh0Ail>&4>BH^J{Lz zn+K_7Cu;HM(+-f~fyBs9<^pP&06Qc3pA?gc240r%`Rej63m31GF6vH z3dP);+uX_sY{j;|f&4T=`DV8I^(9+H<1~6MW3&9r6|CR}uN6My0YNF>y)WKxs zVFSvQ{r^e0SxQ;*dK(jiRHJmUyEOKxcHO8wiDrd=Giv9r_;8;o%fRumLag0rfN&vJu zjzAj1cJ?s|3mvJ7J~sH7wV%(AmC%dACmK%EYg;eHN(sF-J^(iC7N+*vzWoi*qOy8O zWfQA+x|oU!tnq~}Z5X%iHd*hM&w4~RkV%&=sCXudu4^b>&?k&c1t@(96|Jn>%o3u|XFx#;N)>O1b z1@z;M*+E`~a=$%VsA4Jg(R=K`@0tQp_H#W*$Kt&tYW9xDU}UT_NYX0Bg7O#}=-eQz z`1`3BT7NErT(kZn^H~3Q1nFb_7o+id`U@~oR&Y*XB&VqwRNu}P3WaC=ayDj~blzQG z;L0--GxHm3fOv_`H8ubjYl59GWF&3hjrnQc%Y0$>k(>5*7dvLkj(?>M_-T$&;)6CR z(4WF1$P=kZj>M92&{Z*)eMMQ~k$j?JK3Yhx97ukW)-z`;Go|6Y4Yuv|#b~6Y^pn6m zj7ZKH)=6^M=@ROUD9)!O)o>I#)eAz%CYPHom*Zltn%w) zERnKu-wjYaFS-b_dyqZAge=p8NwEo}kWo?A0wj|h81o}f5hzg3$4CSY<&9xJfecPT z{ZFT4mneLaDI3i(uZPUkotee*-aw6_Vh2xM9wjOWAb^N#A^ zV6Kg*lQWus@%SiZJU0ZmH$VETHKbQ9(>5+!Ea zY_#+|iX6AI_V%y?`M{nDz?zx}BY+xy1PYDQMrrEtC~8!{b-~)#Qz))>PN?A$0uH8w z`&g^?Yr2gSyvkSo9_@H}YyRU(Qmr1HPMqEdL{OaRaB(6(lQvz2HmT69=+l6kt^7~tT zh@xe_PUsAugBfsx3mDHM%CMNu;nIt%hGk^N70oEgZ#pMNA{ao<-rZvA7(*_@7{6B~(Bejqx2_-a?vj9vy|t3KeETT1D z$$=la3udf^wrIxOr|FA!Y+l$>sGrPYVZrj^GHVPss=BRkxP&duVNDZU(0F2G+=qMd z3WaC|SP-x>5Mpxm^m(>QMj^3Wke;k&$bujPNb;eLilSMF3?p}#dXLmYaBn#JlvOcB zi&NW(5z!3nR*5&5Xy%gEu%Y$QNUj*>-rPMTi-+xp47mDjCMjI~wihzsu^+K)fdL!% znQ+=LaoKn1!Ln1MVFZV!2emY~Ougm?B>jUpsX-r_LR_)aODm~?B=q?v2_oh@up^D1BVjfK zAA_1_D8@Z|0YXyfKH_(~@)ga4VjS-(-l1u8i*M`1Xs#$(Dz^j=eHeawEbF6#DeQ4L zw8_zto7u>rSS2}j1OhsNbn?6rtS77O|x7iI{QH^py6Dw!6S!N411d~go)4vpOf)VTy5!E_(0 zt0zS%^wI}gF_Z4!hn)q+A0Mx`BUwuVpLvg9G|oAkz|$0Hjf6=&507uLYpL|XnyDE> zzEt|4Iw_@Wv=kASW9@Zr?%08M_Bu_D+yXLQ-Yiln$#MpqL`sy>SH6s!7Of>9$Qn8{ zwf0l6@gp`!A}N?QDm2;D9ySLx6{A4#um|9uHEOemrl5oB+Y zSRSd<+MU8yV^KqIQrMt&3YeBOHrR|~T1w+YyI~>E16P8Ti$0}T=?zOz@=IZIR6?wj zq=g}j-r(0Gze)bmv;l#`eKUn{rjG_53wy@3knuehg$+^+X8Y6u#9|lkRfzG5$lX8< zSp!w=00Nj@m;pmoT5{D8)q;Ik88#{kI}yxJ+HP;eD6u*9V!>(lam~mKN+r%Fwuv|Knr<^3|_nF-i*DlhmoajfzYf*1dKs0FkyY3YNTxAVi z8nJ=8h>YfmIzb{}z|ar3Dp00@@pyR-4)*b0df#DFyB%aEgK6&=mus6xoeAW%!>gz$ zFIozMrjU(%?saj!$!kzBHGVLbOP2}}O)$+SQVC<#uNX38p@-p%0#W6t}Wi9s;VOyZ|2+QYexV^1MoV%4`9n4jG9R=#&8`rKilc(kZhKCpPIRa~D~gr7HW= zjB6p7UL{i|HaXaYm@=?;m!yM!UNU8#lunuZ=S!!|em-p%_k&YrT0eKM8&xii2lnEYFn61TahehT)t3QN$qcp(UOvVyVR6T96O ztj$(ge0$weaX+;S1J5i4x14%7Y$VGYml2QEwvHiLauW$!y}QEaK@@5*JURCU0$_1P z0OBX-7N43In6a#G;LKJW{_p9+vJsso!h=Tv9veF{s~BEsJeThZDqH)r#lm#|*=iK5 zk)Ps9Ymrf1&--yGwR39$8aC~dvb-Nn^_8P^0)XqarD(Z=qLlTm3U4z>4)yz4)NixN z9Etsi)pFgO{1$OCQMD)Lu$&7(jiMlGr|Ey}O(aaoUgDZDQ|v<6g!R;{@gQaKR%4La z&I^lHlvTb`Vqz+-VOBtehz&;cI#n3fue%drICElTxk3NBC??y_R_~$EQ_(+;Iji(ywl6&&j7Z@Q<@BZp7aW2rc|RvkT=%P*@!cV za@!%TO_mI_%(z%Sk!tV6L#EESog@nB)Fw`N*?(UM~yFF_X~%4C4q zBWG-4URvwzb~ZF395dKi?zq92SfoV>2`L!I5Y~wAI6}f$G`uSnsN@QG+SL9se&*dE z`rT8=x3QrX+#!3{0&H@}BszvlWk80_%?!*RJurjyH#&e+O>pN}@hD}n%X=f2!M!nE8Wy5ei35J2Cscj&`Y3)0p>*9u{b0-s{+=NenjmG`LTYD6Vl zkaY(QE_XM3t&kPEEtE$r2BQ!Y#JhGl05hvmq|tD!fvy#Hr!^wwkD@p|E+GO8s*2qS zdXH%O8+PxAz>TP|N2}PrWN)=RixxK<u7~r+ zJTFf@jpjCL!Elejj&e83Iz>^U&ZB9?{az}1!4FB61t)=A*`0}W+p^KfIGNNii{|ZyF{qn2Zw7$^Sd89+{D7*F zs3^UHze|m)&}f}N%7Ae@5ZQ^nq3tz74VX83`LGO)n+_mi7n>kWlk)N{#>%`h#U;dD zRTK~v>OBm-SP48%)kq-K8@oRXQc3OUPcg+4EwB^^&Q28gd`M(tM0tevuS0h0l1xzG zq^IyW#Lj#)%mGxyrg_V~R&53UF8ajHypF;qEu8Md)NMGdTW-i1e_VtseFmDt=(WE9 z*DppBcIL`4L+w;FuhW)|sv3@RZsHN~B((>;kr-*D_+*F&iA8WRWRt%#2hGuTnwv#E zoyP2D>C4BGxWL7LUE{VmBo{Yc`C)D=-Cm3lyOY;aL?9mYb6{N=^TX6#kNb%FV)P-N zMTHIkhDS0&?Z1Ut;BS6mIentyZa4 zTxP=CEE5UMf^#DVNG#|BG3-yQ$-ob#>|VRl;_0a_&9;yR(I?^(vDW0h5R9|gYdX9b zX@HdnOoY(aY%CPP*k|qZ@lvR z502-_DDxB4`&(Eik%zE7D~o^8e+;Rz^F4Vg7gMd1>5AFOo$?9-s; zNO#}hQXy3PI?&Mh99XN(4ZjUeFtQA6Q4YKZe;B{}-2^4l1*`|_ru7}XJA}7OiKAx}Z)W7Pu}=#j|63+E`HicRz-ZDksuK z#XC(EK}8cE4STNoBJl>^u9ZaCZYw70fz`pts!YqH$wDzZaAk{DmO1k1Lq5z;Jw97M zEbs0N4ota>@XR40HE|EXu%{55IJ*ftw4C9fleJkiT9=I$L>JkO5oJ4hOYIzm@=>iB zYX2PGWspyuF(5i&mNChflFzOaiQ&0oBIS3(*xVs30>vW^SBLpC#~onw@;Ho_c<}5h zih)I^dH{|GAy&{#7aHQ=tyz_8TKjONzL=kSayhZssMXn3B_5MIi8EwR;t)d8kHl4< zeU6t!jP>q|^B!|DiR>=rL5TT4+$kX5pQ;Yl2$M@Xj#a-Is|>aQfr|NWwjsb$S%F zc+&Woean^C5Ku#x>`XAqdUMYx_tRX z`r%514i`Tr=~ef3p#k%@dSf9- z-$Ez|YGPgRjU27Q+=o&CK*oAFs+aUy+$~>s9x&;kfX5u%Y;YLMcx>^24a+Ns0~0qR z%7D!aE`F`3V8G<1P0(5njeU~|t^k>8bBZp?KW7(_RDeo~Exfu7w8CYHlNB+})eDLn zgG!9y0zB;n#f!!&jZ9Rg0i##kY69)v+q_TPtRRDh#lsebmye6`nSXQHZlVnbXtZ%n zt|ZQIK@x`$l71F$UDsGxn2ujCjq*+?8@;ysHQNc}yfa!41G%eI7EjEmVI8Qx4W>1_ zbz=pbwhzpa7r%#d?f=!_4Dn^&S*7WoPC#ub8m13inYm{M!p=j#*~qbSPzmuvt_lU4 zjx8YApsC*l1slhH9YO7ZwAB@)lVxh^xO&vE)tBf7N;w}>B9tUQ+HBcp^B`0Z_u5JuJqi$a#<#AoO zr<)R62bKU8+QdjYELd+yB?rj2eG(GC+tXcu3#z)&i%Hd2wapDwO&_Vni|Gh$Fb^!Y z!V}ZpXtPLQIhV;|BE+=6mPHyukK5ldDZrrJXeghXNb`#%zmQ;Z{wG5z8DNbR%}=x8 z?4336Ar(bCW1TC71a&v?_~xv=7s>cYo=KtSHTO&@Ivb6H zu?u|v-x|I>fCp17S|5|axh<_Nj;6++FGUIIk&!V1*8h{DV%q7%SH9FHp!&pdYfL|L z^SUtosKquo*bB*I;KKpIb!eC_t@6j=&Ys_r2{xanv^yEV_#O>fg>xQ7qCq`r3kspHk8=b2bECYAeZ7Ka_4tSZ@CB__VlSc7z(!|$e^+w>`bGlFsl-( zpNh`hjb=@EKrnA<$7sq0)%$QAaJu19CAMB*PUa<0m8be=ip817Cq)f4WDGW48_9?B z_Ql60!#Ne9lg-GL;wW=d#PDV`PCLknaby!}GW%=T#sF2%VJl?2ftuCR>Z&P2W8lt7 zD*l`^#{|GRng)1H2Kf&-m(05*z1tx{vl)|a$l(U!8TP=^l3m?q(qTzERuxnorLCfy zdEk0rc27WXu@RV!4W7ZK>$udo(0|6L@u~LN1|XC5#m=^+%=y6XVx{-RPo-U5b(igb=_6deGqpOdZ?cJg`Wi z5&c(z9B~6_OUEwL2b1TR(jekwvE@{r>0iL6w*L$!rs8ZAoG*#{gi$qF(2k8=BVqpa zNz)=Ws=~Yk5?$Y5r{xaLJp&``0KA}euBSP}H-s-*RFv(KDY$!PRwN-(UDr9uBmkg{ zC;t6;QI1fk)=mNXVvvRTLh1mRviM?R7&AQs9_T#hH{PR@lK7biZ=n zwFQb95KL9g6NPJXV}0TN$%A$`9@~KmZ_V3=Yp3Hzjc!GKYcG$W3ImDkNOc!hIvUeNpEm66^RBySQxRW*^OSDWa42i-ZUGXM`4Ze$z-a6{TI5Jz zJs1bGa>1heJ|{bxm$1q3rO8bfV171F1MD{4v%fDS?=eU`3)7eEP}g-2=8A<6k2`lF ziJQ=#-()a#tKTrU!Fhf}8ytSsuP!6hukO!{L-(yPX?m?~02lYy;RUki$AGcz-dA zq6_tm0p+VYa@OvXNkdpu?S(?#f8|6s0Jb8-Q;>7vse8 z2|xA+?Mv*QGjn`V9a=i;^gzkg#lt!LT=L5>U0UOHMPtz=tj$h9D!N{%6n91OP}aPz z7=AU>R_;~tY;#CCNwr%w#U6e;NDeQ89xBvmbyx-Gx!GlGGw;-X7s=!Sy*UbR<$~sV zdrfnrT(dfZIzWFo8(9jD;roKMB2y0G4Dy}eVBF4Uum|-_fyzs*6jM(dUd8#oO7yZEYSE0pPtbDt>CFRB@vG=tXJ31~l+Ed?#Qn(Zvd% zg9SMb^V=aaZm~j|?Tb<2QW(u`mYn+2#DYt{(Q_V1Di}T>KT;-{1Ye2EUVM!%(79j*0)lJi;+HKT&zP#7X!~7ThFri=78s8&72_>z z!081xNJh-Zd69}yfFJKOW3vY1MG?^oA!6pP^jB&+o6Qd#l~S=$X&)_2x;+e#>)$d% z^wO{x5L~VVUNTGF_|h3_hHuv0!Y^hmU(1=#LU=*4arSprL#K*feARXe$@cg8RfG6FF#}nQ0O|kSn1cyCez7$Sxb88-3RK|E-Eoa|aWgP&8T zDth^z=9{)=Slpsw&bt(bMf*d{RJdEVG`k-|=7xm%o~QIt&;sArEv;Y0=7dIuL^ zHk>AhWCMQPCWcpd1l_eiD&DO|&NUY&m|*Eir?3LcV%U^ve$!#JQl^Eb8HIgB{dBiH zd}xSekZUfyff4VqQQ-wuKgA*ePJXYAH{HU)NCtImYEP!(6qF+!J+zdXeXwmhcTNft zCbT~1V7NEAfboECnn7buM)Q5*bo zP?PfnctXptE(T7tcm_N2&|5b{aVfeUE#d>$GujAsm%OH0+_jWBAe`t3F6A$|%DThL z$kcYAFB@k2_IH5D*R?cp?xp?_nph{DL>gO@ zkO8qqYGV2?N#2JNeP8l6BlSa+`~WUwMi(4~E~AxeFuI1p?QFuAw3i+?pT{C}DZCQ* zsBm628@9~(U1lJi-)g0@n0o#iOpn{P#9L6wYQ*1+Y$wGB1<<`b0`!tM18mEimySpR zJjoPI*UGz~-mBFbJ6kmSH6Q&d2>;p&+ELhh{9}wgKq`RGn@poHswq*A1G_h~Q9x^= z*i9oxU1od!$E2TGrX#tshE(rW6gNjnu3Kh&M|e3E0@4OrL0cFrcU@uE%88*un5r5c z=%Kxm(7e=2TYag(VIh-G1rz zBmdg&3(YsD@ry4eqagft33GIXS53LKZT)iv9I>@|+Dpw1CnCceYKq@E6NUGWAXIzw zNimw;CE0gpqXD;*uOEoy>r{AyN3SW|{N9churNQ6*XVEQnGUm$cD{Z^{rnNW2gm*6 zF&$^{&H7wae}$Wq-B8pUf{GJZ>`=_DsC$6I;@0 z0}oe8W?B*Oolr;{dbb)S?I5o&zKy>DhUELAp(}j;^$?EXAcWSOoZyD~W^}b)+ItQo zEC9`k?X`W|+A|Rr7yDa~^eM0OuP>p)BGraHd5>mWEY0vb5YYEQ3#d_h1oU-#x3xFR zj0H;JxP>_GJE!Be`!0_Evd?!T&RK7;^aL%f`*5N8vU&3oBf(~}A35|G1x%4h6;Et` z;J*>goq|f%M0`G~WBSeX&qgOQneErG@ax<73Wp(Vjs?vFg~HQD5Ie6L__|ld{IKq& zaiM}3gM_-liF`CgT}@qnw`qY}PIYSsQ65^aZm@&PIA)o;!AbJWSxgY?;_5qn9kGkz zcFqEY@lY42TFmZ3bL;|@!K%!6$?+`>`c63%HoFmVt*~{{1?-&T`-?Ds^TvgD{hL8z zg7w3L-JYyOr3M^dD}t^blleFhH4TVPqhv|`d5|R^YiG4x;gv+Ae?-8v_Gc9`gPfhk z{0m46PsqH~ImTB4me|{lT`sFXS2j3nm z%jk#-I~SRv1Qua?J3N@r4{|iFndmDJw_$rl1ul3T8Zef;bJ1WS5`CkB--%RT9E%+1 zDk^Xt;;@#|jRFrtBw3pXLctYJ9by>Egc@fA#m@jSm#iX1wo1}esiW1fh=uJU&KP)F(HbV`^ z^OjTQJJio+L>n=i3{#)_OPkDGX}jP)fzr6M6I!T; zlYsu*Lx0roT!#yDV^6MPr8UYw97hB7d>&2>pITagw|l8sG{$xC3vVf?I{kQ7xdno% zV~LHlFvRW6!ubtst~43ut0^cyE)06?M|my`>CEC?8093ws3;L0N#)18eiG$V94ubg z=*q*xU8a4uJt(aD+*4sAQ!-2U>Nml-J-_-ewk(99m;432hm5ZO{3+c*epXaIXX<^I zR6jL3Y}7E@PuQQRX+dI-Tz+<{a%&XQ`oE${zX$`$gX z509Jeyp&|$44|btcPeEs)`-pH=G_4rcCLGwfWxTg5;#o#374-M_-Vi_sP3f4Rie~s zb{OL^3oE953XkCGw-Zx_RJV8js=l3=95|zbC2V+^3p8e#wT~XD)iFkz3*(7zsz_uF&RA~Uh@$({S7K=Pn{B_V!uFel@Eo8 zzcfB%r|aH?Z{=Vq#YV$tg0pW^I0kWWnbA8Xe)OyJ!G+g8!umH1goCg({WP%3w?fxn z8sB!x-H1@n*WnuWQUj=Nv(+GCE)*S!(awy5tNLLj@RDC$1dj7v4;oe%_$PdcnugVd z{>owm-xhWRxBze3!zTzH(~cRzj=O{}qT`@N;F(+!0G?oRaB7MyhUp10{8@&q{kF{z0SlYM!u(fsjC~NojQO*V)BTLPNQzeGNGA6=u#=%RaX2H)h z2+CsQf7e_ma?Ho2Psp=th}Rxk??+4(g{(&8p*jXxHXY^QB={4_+O7dSq* z=V*Q{WlKo4%`WJ`E)QxfjZ?TPZY%4XhO_dnfKHs#q${TKsenq@dV#eYd z4}1ewiRr4;XjN*i`Vxk!Ro?iO@1vcQTqx`EJ<&@q45r4@w2X`t{hl(ZY z!ljh1@F|LdFo0XLk|Er#buskxn8v~9wbIuUi2kNyll@PImZ1i^oLt@$YkP8GPp#@x z$tC?0*Yjj6lc8nW{7sLM;l1U$knDdlvsGpCSsHQPln1+BehVbR>@CaB9j#-LuHyl(yk5)DBzZfvWHsbkFi317M1Py{%k2 zl$W?gu?OX$UUz4LnY&Rh+L!f?UTPQlj+#V2@ZA=tr*-@r}ab~n|uy2|#gFmcc=O&dnK_@gh!6el=L8Wv$!A&I(3NEE?3hvW&PRU;8XO*vfqI{ivRYtQar&oP( zt!kAwzIxtB?S`bisV$MTAM3D!VSh4D5}2bK)N{&K%~2nYO&m!Wqz-<6|&XqsC9G0SIjX-Y->YlEy9%8?-61b<;p^55$j@f; zS)|vpk&X54-TCOf+<4+wZS#VDK)V?m-$&eqqhVP*!$d$$H&9R5FdP*R7*ri- zy`8U(L`C*tAMPJsm>06JoL;RF05>YmFYuAi~}PVN}iKH`ru7J?@h2Huq&?yZvV9d=~7t zL+?k?Fy1z{wjG+Cp(B!*M>!9P*&l@=hb_`-jxlBzc1sdx(qtOWqRQ?Vb5SmI+wUex z8gs+D+l;MX+85#AnR zBu$l`jg>nZD|<3_sm#IHmpB)zInv!XxKs%9(|yP6bcKYteX8_m>Prdq)uEM9gnamzp)K7il$;Qi9uSo|A1ZS^^yN;6R)_YZ zhqm;Prpy`5mph_a9ifjNp)&iaGDjs}?4)FMgg$zN$~^{L<_TaZTj_^?%RKk{r5^cR z9mkIy$HtC6eDnAH)pbGjg?D(N=TT@x0PMmHEOyKo&r8_{7=>LU#eGAq>w5lW=bp@3 zYFSW~*VW)~-hRAFisJ_$%xyiq@hkLnMxcizMQ|Tq>VU8D^7Cx5fHRi}dKRI9?`&_x zQAa7{_xh@+7Y`+LzPlN(LAJ`9Mj^S~j{;+lJ6H$O8=E#NGanKoRz9<{c%~w=rx$xj ze1W7fsA=hWTUczbc*k%F6ocAV2AO|~H*;zHLI;X!#u>|e&*tih$3fGpLSeM84PUMx zWR5)gkPq`ykI&W*FUfB0z?9~sJBKvqeT1mar+}F_y9qD*YI!M$29I39!tL5D65y29ISQc6v0AKrdn%uhYJ>MPv7ksi%GqhO|y+k2Ea+hbOJw_A{Bg_)JmCxAPRK<@e;yk>mQ^&CcU zS5Sws7_GBqY(Np?nHw0mby{k$76dqrX|va1P&YmYQz{>_rKkepg8JpDFzt z*uSBnt3zuHH6Jmw-^BiHb!cU(e$1@>nRf@PBlM9Yl(KhDB^S%IowLNonYM3!nr+kC zYhk$)(DlFu?J0%EY7!g!bp*8srs>JhGLJbWm$HNzGHHTLnIADkSV$QQISR}}?^gX*a}U>0W_$)K_x z>^GyQ)h1IltQN(syel3}cWl8u<96_yJg0Xbt^;#r;fy;ilGsWV}GY_2V!z0H;K7u< zUZCOy9@9eM@yi8ZWbeS4%NehCa&_-85VIYdf+~DN56}`+&Z)E3fV6V^7Hyxr=y83kng{jw9ylFi?m>Xg1Jw4usJQMo>k9I@207;ZvrfI<-QL z>ct^I2R;%drQ@4NQ72EsVEPxU|8BHou9`u-~8*VsTX%i;3Jy zb6NRZ{)v`SgN6{X#Hu0KQqzW@r%LP_g8o8A4k^q2^vH0#=PL|%MCMIo!UvMhB+^%r zxkbwG1%qqmn!zym)*5T}1{^vGlUUcogZA0oAkS)9Ori2)dq44!cu)^8psG z!-B6X`0qsD2CY&ISh%ZY;!WlU#<&J!=$I`{GiRa6;V#EA2Sr4Qx=!DKX_ zytrh?kK<*`tfpXw6BZil-H0-G+NpVK{Y91ym~b zbAxt@CL|Nf)cJ{xKmx3gUH#0d5{NGE>M<6oanb z6*t`TQIA9|H-DF(!KzG`{Z#StA1fB=|00U6DzC>bzHdBHF&{0IY6{S0P6l1>ojG2X z995R}MPGk1v63YSARl+e$?4NCWI>O5kc>f=Q-T?e!u5WXW|7zQT=ruU6LrSZhcH!r za5Fnt?i0p%-;(r2ONZ6Yt_b+@DemMd9^WyKwa?nTRTXXQP!!hCYn2SumQ;U&@}x)c z*b5O{8|7m{60$mz3g{Az&}1Bm?vxIbL>0wGX;LMB7owe;#s`u(6Y65k_IZI+{N=fP z-`b$eoDRx7!Wyjf3@aWEeIJv~RkNwgQ>>tiKE@i9JjWW8KFC_;N!D_YvX*<673ycn z!>qw*>C>!bA7?H5(BldZw3<$r8@qC&R&Kn?j+7ZAN6~US$PyD@>CUmtu5qe#$N0r| zi>qG{!+_oS)qO!MUo8287#dV^kD}xvMd?k7GFK_e+@<(Zmnl{s?18La>A@a6i;;Y= z=jkmK4cDGo-$K+Q$5Bri zarlq*tO^BC?5hz9-xA}jKJE8WLZQsi;sRBPP|#~u38@g26$?Q*x$wmV1662aSHw$H zPMB+nKzSffgQjn{Mo(o=fMgaag4Z*0Pk1&IG$@W4 z_NQ@mxKohEAsZgXN#-@dAI9OXWj>v^QS8OZyj^%(ODbJ`Rz7;*r`v^Yyz={7eF*!V zXueKg-id&LnMNs1gLEGyZxM$}FRmg{63mV#2ztXiUW6%y7GLzmf!XNH)OmsDru_EKF@~vvEF?K`$1ZF%xzbAo^H#!WLl)Z273y@_ou3Z zHOI&+HZ7k5?l)HP%p-?I{!!hA@ts@4trU#2f$T&rm>&*15A=<*h2L*RRk4Hcf=xTuxsBUK?1NR#X*a1SY4D! zzU9j6Y%$Efx`QJW0Jo+b*?1z_a{`HVKMQS=TX(REe{9M`P(1!zOiT*s8_^*q(Ug)L zrA=`zCy-TBW@ny224{^)B#GRJ3F&$%oiYE01Tta?Heh$-S}%~&8uMc&WwJ?u znUyJImrTnflCM~9PW5PqotSaTszZDyGiGMlsmXLc$lUaVV7T58EV5@5~eHNrd^P?zytpr|Ek)%vbOG#I5R$@~5An8s4lb(}hrzA3$&d9P8vg~{; zI~~i;#Q|SU)UU3?nW+M_gEDjmElcR^ z=*yxAKcUfQ^#OKKtd@H>0S?>4)Vm4F3`Q9PTp9aY7x^G%C{0=4N;T_Jy}Ha^yPQs4 zMx*}RjdrQvaGb54Qf4OqB9;!pdOs4g`ek%nmHT!qF{`h|0Du43cPHpFVde)Xh=2|1 z;$VZ~ApWZgY7b1qlOY`17_|L$I`KDPERK8P>HMxYIs|e5T;CXlbecllZxm$}A;0z3 z|4FErs>r@9#8h=jl#Ho!hQ#Sq@?{GI%>6i;6Y9`xG-qrBCNogj!A3JmP-8Q|mB&bIJ8&&c4?!z?LVt|ngEf0or~`TP zBygPSOf*t0WyGlQ0eO-pS(c>v=}=$IgwpY#t?jn-7la|1#mJ`P;9J)W;hb4bg0VeK zg4U3x!(%LHsiFA>f=V0o36KnxFt%r3aZ80;$&uYMl)u+YEEWk)*2I3kAHvnY$|vr& zAnzsE^KzPxE^vTn-Xr%0H(?(CvPm0gitP69@K$ttMnIFQaU2#xq_cU%nZey=Tz`&n zVDm!MlS%Xq@fRkll2c3bsLRsSudd?KO#j9&f(tUUdWE5>NfjSs`2(}bN6}sYJHk#V( zXoGhI=J%CrhRrKZoOi{b(gw)^$xtb``xTVxafnT<$u@OzX|~AJ3T?4d$%WctfAo57 z)Bk`&gYJMD;FUR6KX~5Z_zUzA64qikq81IQ8*IkYsI-4e8g=E1b_k@ge2$_F);w*C z5-i85@VsKuN*>LIR5)kCubru}0F6I*E^R60$P#ue<;60LI91ApUxWpvudA=xiN%bJ znjLF1xMpm9e;MlsvXxrLSXLPe8PVmeWW<-Tlo9>8)-smi!K%1P3zq7481rvf+>~L- zGW=MM8Ow5FIX3(fJh&=u?CPRgjZDfP5I0QIIEC8-+ot?SdbZ6+Gr_h6^CeC*xe;2} zv2!t6a5uh#?F-TTwq1+(F-iD48_hTJ$3q1#rf|0TVyfhfHO}>MKE6;Toay6b6btd& zEynj)RJ-lDIA;af0smqbKH=NYwFobfyW#35d}{{~z^>svP*B|s@YA@p zsq|hf(l=}(ad1DT7ki3kAJ>e``P3`UE9D_Zqd2&Q*JAEl;T74_e54@FU?>$_S)#0Wq!@G0DM~R>K zOC?xIe*@^n>j$dbl4v~m4ny=(>{0MYv4ZDEr-#i>C4q-d9olW9!}Fx9<03Z}1Kch0Adhh@hmX*X zxEwD-pSf^k9z`-13#t1c(lEmgw)3%|%nuqhe=yi%`t@)_X6wFVnV86;K(x=XzSq&-R~-&CU)FPmV-zTiiHCH@m=?0@t>H==#DYheaHiX3!+@ zv0PkBv0yxFA@tJjn6h6L*Etkqww)b7f+@Q`!W+XYi;N`%=5D;=#R(&Qha;K+EE~hm zSIE`bRLjnzvD*#Kr9}`uo3?K{(h`^m3-|+@*p|ysEvys!4cfy75IK{uZR%L4Sn5F< z&+281tDYv>nj73JCd8DX>qxosZMUt*_+Vq%E9zbbBiM~Is;JXwYz%W-2_RxHPd zUxo=+#f?>WoumFJKH|jRR-!5w(gvUDWtb6XC(5U@^)aaXN6e zJqXU_yMoHretb=Dy8mpo)-P^q^pk_18vFFnPo+lwvj)DZwSTElnC(B+l0%Dwy{-eI zE$-oCA`XJ!4fM?xP`q;AwFT;!7-UrmPZX{N!4j1J`zH@>(7p;^Ab;WQJ=u)bijrjt z93>;Hy*#2!7R|4hY?Vz%&pjAq#rMwS2cf?SRAJYb1>MivFh@25*_o5Vm-$OfMw;(o7HiJ<0SXDk79lYY?zwit!XR z)C4a-J5{+=J{51Hq2vSlZ3s@??GJ^e+iqh05?L9uG-hRxBu(TrjT0nJQ#eiF6n#r{ zk`j%iR39m$jg;ylpRI|k&S5htzVsaS7OwQ*r^miz=u1bwWZ*w*+<%F)-7Q>hQTqgs zunO|2>v=y8rB7370UAarijo4&&o_dKchYJuVrLYzKe1--tOy$Q!|tKEX#Qw285NcJ zB#K7V#Em|@B7L$D`3IDe;c(*BqeL}lpCpS4PKNd>Y>Xe(tFVIV2;1T)@!?c6g@J9T z1e3PSs%Xh1A~Y3yzNE@T7n65*BWJ7pt=A z0?!9Ibi3Jp2QS#RV|f>zzGQUUy6(YTvGCz>=T0X0(a@VbctyVC!}2WXMj@LnZ~M~} zregF+3ez*1LIe|yNlbb%Kx}$F0IFn30IqaZ0J3CZ0PeHa2IMC=Qh$O+3s4tDs8`(| zhf=AisWpsJ6eR_kpKk;ePvg&#lIEQcN!eqVI4OP1`yNvAN3NwO$yM==Vl{~~7u1uu z4-M{201*Jw3FCLaG9YDTQM!(0hc4BYpD$ghbSfvG%1WrRG75XGvQnzPq;4A!<@;+kOuYoZ5&JgaBNAZ77ZW02W?3q{+5 zxXM=`jfEjy6D!p66ZKY^LioGw?nD?)-nCXdi~q`b$h6Y%kn)YenLew&VsM6s#E)o$ z!>{_)WrX_G{kd__M6B(!38$*2t+1f|1fP;Axda7H_)72AsjT2&s2{`;umdFiSXSux zQ&B|}6B)39ZxQ!R$PG~W+hHt~A7l;n3nN*EQNJfY>^?}C$!8+~|r`eih=&eiK4QtT261#v&yaj9LT23&{8tXL*$33xdm*R zk*KJ9tS)>oK(gbw?Xr0A!*_;t!0p6ai{d*{4bb!U@_oZ$gC>NF!=%L~m=AE6=D}Mm z-MFpeVc@Mt0a2koiIjIFC(q2704Y=HelDb?I2zz~8`2yg1mb2{u?(y=8@Q;{fm`|- zS?b8G^zztL>d@_TuZ)?NyWd2Ah%JxM?sUktYe^=kL-=koJPxrl9}QFQQUpFGXfAZw z-RIi((V{=TTdYmfmza~QogOl`vTi_wJDF62IH?Nl_s z(L_n3s)nPSvv;tSPg0k|Zg?tb2`!M}$AGP`a_L8v^kYVyHN8a${vYL2Mr&h zaqsNxcrJRRns*RX+>VMy07>rkZ=$)~S`JQl=cCuPaS+$v==;OSD_@P*ih1^%*e#Z%s2dK4>oobtyQ#*O@KmrfoJg2<0c6pGZ>Z;H=I* zpES$)OI{$B9{ZA^FCF=kf&YwgU#^`i;B~-%hs;LXor?4C!oqByTaas^mlKw3e8z?g z`q`axh&!OPpo^Pmt$vty>U`BJF|Q$O>Y$4g5G++MvuPsOh(h#iQN|6Y|X7`@u}0bu08d|vp+i%Gc!3W6Ejk0 zqyKF$|D#@b`XT=CT;elc@%OuAd6qR-7Gm+ql4~Mp$p=ehLb25w<9yo!bhV?nwW)6^ zHSfbTufXgg?S=yLqRW<{!el2ltF_~U52A^>eUsz+Yu`ophR1Qwuk!M2aqtkS7Ta)Q zn_&D*r1vnS_Y`FM@yDt&{c|B6hCLq7gENka=j?2$zT8+wf}RTM2z#K2mjSEB5d^B!&F!Kyw@T0L`Khn7G4W>zi<& zpg%*Wp#ImM;)Pc38S&U6((8t^a0!Ulc>JvHPR`(Rcc5qwKUbmQZA@dqQL==)@>p`z zx!`h3xVX>}=M@ZoLLMn3pnw(wA#LQ3^?x%c=@73p11>C~+2IY-ZL_zret9UTa79vC ze|wrb-T5~*_WkNjsJ{SaBkdJKF38%0r2nOJG zL3E;-y&&tLe_#FX#?&!U}9gMwSchFbXlBd7=TD zR-@c$lzR+8o(-d1G$P1kqhbSGSk5>rFjwYl=zfsL;e+5U`wCDxs4Miq4PQ>Jg0;?OGwh#BI8w{Fh91J{z zK@atj4(dWoMFr49U5F{th2o0tdN`!Jx@QqSf@pPL+2;$bi(wMFsf*#dfz%u}ar>h= zp`*G5`!zgupOZ#_=a#;4J6CEi_(R$YcY|%Oy4p^4G3>8cfpytVnz__HX+NT+?o-Q8 z>K5?vLV~(aq%erh#I37~VZySSPhQhP3#APE^CN@pPAkI%n{P`__b@Tl&F4#;IMm91 zWJM%59e6h)sWKO9rpMKJn(mi+!}R-6l46Yx{=G>qzLt( za*$1YQ|X~-!=Bx`b=Lbb3S%evZjrswR3c?4W16%&iQsU32a zklEWkJjFHPMmBd#b^?tZ&$zJ8ldu9CPxNsyFAjD!Wdu>x(lfyxOx(faRTkEh@bi5q zP*e;Ruby^ni-XQrbv>KA$p*028>S_h0Tv0OWTbsV6-*7HG&Ihm1413!6Y1(fbaje- zJ`hbZr6Y>-04XV(k-&LOnT?Gzrp$&$OL1E}zBA+19 zrNSwuXjdQgkU6$~FJ_6na%Ve66|c<<0vyqVra(D6^*qwrcB3aYx$ zac>WNWD2!pMTual2BG%@Wt*Ct)DcJAexa2crG-{4Z|5k2#T)kQCfM)*!DwKsMxUV^ zm~7FYJmHt`ay$zBweS%(3?+~`{%9&6W}mlL2M2OShMjg>w8i72a^1KB`k4*y1YdwsGKr-jjeYRmjhT%uvLv=26FDD(E}awOxQV${4o@T z@g`#gd||JohtK6xPZ=EBLcS?qWHCDGM13`=dAe6+xmM=^rdtn3$c)<*$PV`?m(^A5YZ+^IbnV~V~lSBw8BeQbMrKTcP0jj;I;`@MA^7TOrGQuhU z<#Me5KQ4=-zoz4RmRPm{m2q-{c}v>|P089U>x%mtQ1@p1K&CTAru$ZT7Whj9uFB$-Te-v^>4UL5MsNiJ$1|L;^ zmI3g=Wa(jBh_^jp$2e?WJY`av;BkfMwllRjadJUbm)yAB2N(-n9)hd;lB-nhL47 z9s_0zif1py_sOf?trL+dN=uGS zv5;eZL*Sf5R*skXsm_5rF8Si<@3U@7j*Guui^CqTeZC?V=EOxZhIt@fwVqI2Ja&)C zgTtPz&1+pctJB+CK;6sdweu8@B1I*QANbWwLdW>tl=cUsIC@yJ(PeTJ(kSzBfc`3K z&{b;yj{g}qORn$*d;1GhM@+fYe3 zs#mTmfSae^`v}LrHCTh#>9G3@6%p7_vibMG`Np0>bm}z^@T+>?E)~VUkB6R#i@a7z z0J|}Y8R(JPZRSyzgfIN|mFl34;UUvnrLt!2qGjqt*3V;N8;W7K1NvlaaIC-pAmZsb zF8#3!;LEjFxGv+<$61^iVOrDgT47zqV)G|lcSlOcti87pAu3$cH8gE8khLfD#A*Fx zo+oo8ne_{ERtxzc0|iEP{&r{qCjMn@SFSWBD(&Y` z!&6K=!MtqC;5-%Kw(3VC=p4MBC~Q<0&Hmen(p3}ZroS8O4L<_lN@_`LZe3FK4&tQD z6fFZ0C~DTo77k1F&WchH5BJ!Z+A!9cWm;8A-MnupU|rb>!k31IkNl}n!cCg|?&(4& zJU!vB_gb9M=hW}+dEOJ)R^Gw~eErbHqF@<)EZ&cR%FfJcgO4MFFb#&a)aQ+ zC8K_s5`22mIOeL9F;_Xa=l6r+5!$@BnY4h!doNZD+Sqc0g*uWk3`>u8H4`Iy$+8;c2)=dA=n4{n_ z!`|M5fPMS}b`RgoD7Uk{d$FV$cG!7u&MWyw)sy^zugnlDXd|)B?c18r`8tX*d}h#6 z=TjSAE564SP_}Q~S+TumUxGvmy>|Nl_nmURyp?dyZdk8jk}T@8E#w+SoT+Mohj`S~ zM6cXFwW`3tW4d*p6z*6cvRW|;l5aq?V!{YW2v-wE02?kQa_?jq0gz-1g@0bKu|v=~ zvgNW-CfwK|%J*%WFXG+GNml%-zatrwO_qZGnpIGiHMs0Rcx@BSP-@uo89pA#D<3hF p1I#39Op8e4s4-Q(8grS&7FzR}3|8Ks5wrTh1g$Serial Port: the selected entry is what you have +to use as serialPort variable. + +Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ + +This program is free software: you can redistribute it and/or modify +it under the terms of the version 3 GNU General Public License as +published by the Free Software Foundation. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see . + +*/ + +import processing.serial.*; + +Serial myPort; // Create object from Serial class + + +float [] q = new float [4]; +float [] Euler = new float [3]; // psi, theta, phi + +int lf = 10; // 10 is '\n' in ASCII +byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) + +PFont font; +final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; + +int burst = 32, count = 0; + +void myDelay(int time) { + try { + Thread.sleep(time); + } catch (InterruptedException e) { } +} + +void setup() +{ + size(VIEW_SIZE_X, VIEW_SIZE_Y, P3D); + myPort = new Serial(this, "/dev/ttyUSB9", 115200); + + // The font must be located in the sketch's "data" directory to load successfully + font = loadFont("CourierNew36.vlw"); + + println("Waiting IMU.."); + + myPort.clear(); + + while (myPort.available() == 0) { + myPort.write("v"); + myDelay(1000); + } + println(myPort.readStringUntil('\n')); + myPort.write("q" + char(burst)); + myPort.bufferUntil('\n'); +} + + +float decodeFloat(String inString) { + byte [] inData = new byte[4]; + + if(inString.length() == 8) { + inData[0] = (byte) unhex(inString.substring(0, 2)); + inData[1] = (byte) unhex(inString.substring(2, 4)); + inData[2] = (byte) unhex(inString.substring(4, 6)); + inData[3] = (byte) unhex(inString.substring(6, 8)); + } + + int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); + return Float.intBitsToFloat(intbits); +} + + +void serialEvent(Serial p) { + if(p.available() >= 18) { + String inputString = p.readStringUntil('\n'); + //print(inputString); + if (inputString != null && inputString.length() > 0) { + String [] inputStringArr = split(inputString, ","); + if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements + q[0] = decodeFloat(inputStringArr[0]); + q[1] = decodeFloat(inputStringArr[1]); + q[2] = decodeFloat(inputStringArr[2]); + q[3] = decodeFloat(inputStringArr[3]); + } + } + count = count + 1; + if(burst == count) { // ask more data when burst completed + p.write("q" + char(burst)); + count = 0; + } + } +} + + + +void buildBoxShape() { + //box(60, 10, 40); + noStroke(); + beginShape(QUADS); + + //Z+ (to the drawing area) + fill(#00ff00); + vertex(-30, -5, 20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + //Z- + fill(#0000ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, 5, -20); + vertex(-30, 5, -20); + + //X- + fill(#ff0000); + vertex(-30, -5, -20); + vertex(-30, -5, 20); + vertex(-30, 5, 20); + vertex(-30, 5, -20); + + //X+ + fill(#ffff00); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(30, 5, -20); + + //Y- + fill(#ff00ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(-30, -5, 20); + + //Y+ + fill(#00ffff); + vertex(-30, 5, -20); + vertex(30, 5, -20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + endShape(); +} + + +void drawcompass(float heading, int circlex, int circley, int circlediameter) { + noStroke(); + ellipse(circlex, circley, circlediameter, circlediameter); + fill(#ff0000); + ellipse(circlex, circley, circlediameter/20, circlediameter/20); + stroke(#ff0000); + strokeWeight(4); + line(circlex, circley, circlex - circlediameter/2 * sin(-heading), circley - circlediameter/2 * cos(-heading)); + noStroke(); + fill(#ffffff); + textAlign(CENTER, BOTTOM); + text("N", circlex, circley - circlediameter/2 - 10); + textAlign(CENTER, TOP); + text("S", circlex, circley + circlediameter/2 + 10); + textAlign(RIGHT, CENTER); + text("W", circlex - circlediameter/2 - 10, circley); + textAlign(LEFT, CENTER); + text("E", circlex + circlediameter/2 + 10, circley); +} + + +void drawAngle(float angle, int circlex, int circley, int circlediameter, String title) { + angle = angle + PI/2; + + noStroke(); + ellipse(circlex, circley, circlediameter, circlediameter); + fill(#ff0000); + strokeWeight(4); + stroke(#ff0000); + line(circlex - circlediameter/2 * sin(angle), circley - circlediameter/2 * cos(angle), circlex + circlediameter/2 * sin(angle), circley + circlediameter/2 * cos(angle)); + noStroke(); + fill(#ffffff); + textAlign(CENTER, BOTTOM); + text(title, circlex, circley - circlediameter/2 - 30); +} + +void draw() { + + quaternionToYawPitchRoll(q, Euler); + + background(#000000); + fill(#ffffff); + + textFont(font, 20); + //float temp_decoded = 35.0 + ((float) (temp + 13200)) / 280; + //text("temp:\n" + temp_decoded + " C", 350, 250); + textAlign(LEFT, TOP); + text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 10); + text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 10); + + drawcompass(Euler[0], VIEW_SIZE_X/2 - 250, VIEW_SIZE_Y/2, 200); + drawAngle(Euler[1], VIEW_SIZE_X/2, VIEW_SIZE_Y/2, 200, "Pitch:"); + drawAngle(Euler[2], VIEW_SIZE_X/2 + 250, VIEW_SIZE_Y/2, 200, "Roll:"); +} + + +void quaternionToYawPitchRoll(float [] q, float [] ypr) { + float gx, gy, gz; // estimated gravity direction + + gx = 2 * (q[1]*q[3] - q[0]*q[2]); + gy = 2 * (q[0]*q[1] + q[2]*q[3]); + gz = q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]; + + ypr[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); + ypr[1] = atan2(gx, sqrt(gy*gy + gz*gz)); + ypr[2] = atan2(gy, sqrt(gx*gx + gz*gz)); +} + + diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt new file mode 100644 index 0000000000..94a9ed024d --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw new file mode 100644 index 0000000000000000000000000000000000000000..904771486a1a6d241fb5184282eb99780f730615 GIT binary patch literal 114920 zcmeFa4{%l6_aAiL{l%ElG%aF^6jR<0`9(}4QW23KrYS8_M8uR9DMiYU(niFXrV*tS zX@}7hD*SK3{~yKw@5le&iT_`>{z~f- z&vb;%`2XGb|6TYez83#~2mT3vAO1Jse=YtQNB^(kpTIim@bAZE7y4A(XVm! z@c-Rj9Q|76-w!|A!mzeQ+qo6EjreDnar|F{f5Jb2|8!i1!~{VD+~0@)-;00Er}h0I z;MhiO=iddtwzCm_wnghBO-M_^KZt*p!E#w=*HV+&^N&ewmtYr;RID=09rV{B|m>ca@3L zKKx@V#O*FqpO*QXh+|z!Px_Ufd*CPkDDN_kJWlw>@lRgnKl@Erp$Q)5(KymT;g7(x zT)t)-r!-?a?cX1T|L?&+c|mEdaeIMdTEigq1ZXI0h!*}o#_TiuT z*nf?KSKyz(FXMFF>DPSwZJeJ^l%zH7dJ+QyZm=V2Si@}x|U*8hx+E7$iH8&|HrKZ!Wb)pGfc*nF-&gcbf2 zJnVzcBl?vm{aT~{Y z$p=^A&%#5z-v=Fs6Tq`B%0=emKj#(UpTqxhvhF0}()o1W{yD^P4k<5jjFo1mtY7+$ zaV_9q`~F*qV;R~O=2Lln8h*+Kr8WK9hd&QL+pTn=U*QZq%jNqEh)d_wGXG+kd^(R> zZ9biwEJOSE&%@8Tpl$KndDiCBIOfwb{{tjFrPu{xv~A1Z5-=izv(Ki&s&`4 zW4xC6uh_Io7v@u1|Eo66_1%*%7i^r)Bj!{1EATMv$7z`tfoFN;%KWP~AM>XBa0xih zBkDnn-j!_N#N|%2fezuwaEb{>R{y)GaJitHO z&-xk1_UbzQZ@~WtERJ!Uzd8;N;U`UW9O&2j{!RGFf69Ywlg2%QpJ|nzbQS(Bc$VvX zAL3ZQ*2nhfIQ-l2vt6VU@%*RWLHKv@uXPdc*Y_A<>WaGdlMb5i--Vwv^y#Vf^#jj* zTJG=mcqyeLR^~G zTHgTT*iPjown^#v*Wv$z_~)9zw){blW`irl{U_^9pgZh~qrbeDrI+{{?=| zf1O9a&znbc!29(vo#y*r;ZOHZ`#!%y-2b*h+ydhK`smj(|96{Dd7gDEzx*F7#4WB6 z_kSXeb!eINYnlI-jZ>O2PWzsPpY`jw`(yimuMn48A@2V{9P7|B{rd7N#QndBV;gm? zqF-rNuyI-@(`X<5Kls^hon!QCzHo)O-(DfEh&Z-e%cNh+{9EvUkAKc(;x~AF#{EC# zyvF_hIPN>PcbPTdJC4;deEl8eA=h;Nvp#Qq_>Su==d-rcG>UXlI8OKo)z*@{xP4ng?!V-$_nS6O^D$2I zHNo$kKwb*>xPL`qc{F64Hjsxq~`i{WQ{;4eYdE!q2PugpoC+ENW)4(U%iLiz5j>5BC z|Nac(mdkg1g?xY3=2Jdp89GKMY(BP?G-KTw_vhdzuW3H^RpV$6VS3F+SL1#Qe%7J+ z{Q6D<&pI@pU*DexeiQzcKUtsB`iza!abVqA-(P^Ab!a~NHQ!%^pK?yemVV9G4nJj` z#?i0i{+HnA*l8U78rK0o>(Ds*HSRCN&pv4!{TlaI;3qxVFSeh43*TLYhvoP*(?0xF z;8{*Nnq2~(?bdwsYd-G7*>258zxMqy{L9t%*ATZ{eYX+k^91{0>&tMDKzUBtOg!tO z><47HM_4Xy0&z^I`8Yj_t4gb@)kVk&ho_fTvyl*okw(a{QBW1o&0e}knrp51NlgGsrAsM{x)N9yvh7*n~ppEwhx=h zW9c$Aj&0^R`SocW+r>C7lVxZe$DQrbxL=3g_F*%}kG!L0vJTDnhv5GW{Ie{!k!dY# z=DNvoQMpT3%ls|)ec9^wk20A&p=JJoSjXJ_7j2xjh3&R&`3>&-nNN9;e#@V~%`~h- z%cS4JZ!4{}Ocz((TgdfP-)Hp?Xta+CA%F98{QdBPzt0}?_u)PM_H^*~)G_`ZImF-n z4gB3u$=^(X%()<#h@y8vaA;xSpf@2YKe<@B4_d4!_T$r|{tS zVe|kV{N9Xi!GqsZ(Mfpl+Y+_FgWr7-xf8$D5r-eYnIhbPzpv>D2IMzrFK{_%D|DM+ z5G=6?!CWNC;mb&y%&(-Wjw0;X%&#E!MA1+Xm|sDF22apc`4z-*5HbkNuOQAwY`Xak zg7*2a2=ZpL=zk%cJ4-tF5C&~Rdd1DPv5+@Wv`2n-Ns(-M1hHp+1r)1ECAx0UqOL04h4bv6~s^!HGt|- zwAE(Gk}Cr9E2u)0hg*ndZGzxp*a2@xcuo;?FN9zb9}JIp7&P7sZSN)3=I>ehRQ9^Q zMN7w#P8eBnb3uSkg;yFfLG9UDU@`vhz|W?}FS3<$+6RQgqKD=;=lm zPv_rJfElPjH_&kzKEbR*3S^tmB$>V_y34{BuI{f4GWBhknprVi5@{fRAXrd8-LV~D z*TVJs&i+M&W*_d?+Ta4=g?<#GWaKUsys|+B3D*>JD9WF$sA$bcnr0vp zMrn-(ZIVJ%L0^UN6@4WLo8_#_aySalRaBfSxI%+#uG)hcpx%f1NK3V)9z3wlky%X(sTJ{UHpS@aZUeyE)i1HrHl( zdqAdoP`Sot0Nqo(0b<#-Hp!SsElm&iMifyb$FLO@`k39w5=Ak;oUmf6Bfx@FoIkrA z;kUt>5FLt6;kd#5j^apW3U|66w%1msMdHnt;R*rR$(a{^k zG(ud(5H7R@J11S3a{{YI=0x9QJ}ON1ZreH^6|S1a%Pd$oWRWrpQ*~6sWytXA=J)wl zHU)j647`MrFy$p5%`jR6N#Of49(Ds_(yhZRb+$(UOz~$&o!=+>) zW5VGC6<5O=uj$E-mywRt;>cz=^-+Fs9qtXdb;!y3vDS+C57vVkY+rB@2(;I=KiKp> zd*)2;{U+cj9mhBiUn5Z$+^y(FVIw>&mm{*4-6Y|OxDIy{+>9Hkgi9`@ zy4*UZ#(@&qh=NV*$^6)rts*(Mc8z6E3Uh%4qEY-u*$MtS z_)!0ZBWIxa1ahY4)PRHr&(xUW$l6iVZ)6dYdM&hQ8#I|3#dWf1b} zH5_y~%iz)M2vx<}k=#iJ1+IinIWh>dT-#VWD9j6eF5(in!h_s}xc3GfUcktBkXKm% z+!t(zEvlrqT^>EQuo+K-pc763oHPKp3ycL$pMr=viQr+B0}1pTPDL1n7(VJ#Lek!7 zRwU(IM12Gz;e|LdVUhDkL&Hcovh^*JzayzaDhVTv#F^skZ{s|fI)+znbrjq-C)Q08 z2>*j|;$U|wdRWv?mjDy)r3=6VX5Qw7q5D4ef|<#vNJ1!_gGQo$xRtX}NI9VZDRWKz zaH|)ioGLR!Uoq2FQ`F|7g=!7Jz3D4MBFttgz3AR3q6Ai`$BM0fx=*6$s2ARD=Z&H; zarUbpE<~v6AcDo9?DC>9@Xx$pfanH4oEJ8UF_-5P(Gs!!-gFpF-&5*dRW310q*Ypo zJdfnfaG&qWWOh7;2lM}Z6x}z)-{*b|%_W->s%9Z^K?@@^fVdDvz2jybkOU1;G!7}^ zR&R)0PD6>49|S%&oGuT7&+#ml{r6~((_Jad-=D^Qw*RE%nR>_!0~6Rz1i_9)4P*7$gLypz zmf{X#0_$iBf%NwBw(VBLUGF_7&2%N9m7z}7ED_6y9s)eKRX-1 z^0B&)$;khMBhjrxdSLY0n`r?kX{#s^)iQhhqHw+`{DvsK)^Zn(m4c0(3Q?mq`!XDbqR}H-wsEVCrsyGo$$CL}?_x1Ox46`E zP=;;Iz7Eoy3RD8xg4Udm_;3(et4}<5y@XyA=AYl%=a)(qG?odQL~6Kr5+#m3h|PT* zgoK-`iGy8Sh+J@UflGx8zKn8MFf|BM97oy)t7na>XM@*`=5Avfigsx=v2S!ekl-md zViFWl2%mwp08qSfjR25-0^#}_w@Og9jC(d-i?BhA1_4DGkNg%Fxk7meGprt>ICsvZ zu*FyhDLw(Q{nmI`n0#PI)T?C>^iH;8b~6x5NHTP4Lr{4NvT6*Rdva;4+0?rM3>|CL z#GOrZGPW-%j!e(1lBu^J`_t1)Mxe6HYOw5OFj;uLsS^95ZRa3L7uUV?T8_B=LCt*% zHw)vUqipKzpUM}*?3;TBSdfK=?tyHWAMG}BuHl*H;l>lvR)b=$rDQ2SICZ^`&cO8VZJs#MT3AyVXSm3vt<5)%H49$o3y0;scmkMZ()U*`2w{qxsE- zB?{eJf(;iiJI6C@+N{x%wr8X0EXHGrBSdJAqE}B~vo;}Ys6cl}j9C1FM!T(&&NNW- zv#?+nWZ6O(ZF?MGmSrzCLTDZyKvhjNNyl)P*>1bA-9c@;HIgsp-`=Q4q>KCU9+oMv z4a)dk&k)$-t&2!dU5J)2_zpVEuHA(pLY18wU$O4!Fc60Zygdmd(Ewz-DF#_r4B=-qMbrfZMAgZH@DpWrd@2&1&90hnT;)q<&FcqG=C!qtXMrlA{EMa|GY zmn{ELaq7c=s}k-E<~Zhag@$1RE`X3u`QS?T#MoRU$sMe7O(^tL3ufG!!!P08E5;qy zfLln{i6RVS4N=#1Jk1u13;peu5bG`v=Zo2=tvUjGb%pp~8oHAWH;`{effbNN3!UqO z%3~vFFy=4>;Jg`a8l|5G0a|j}cA^T2chCmogaT6E4bV-S0NZTv63-E=ren1IN_3Q4 zAHp6AxwROHtZk4Owb#%bl)F$HY`h{3gvDk(DvKe9thFy}c<#Kh0Ail>&4>BH^J{Lz zn+K_7Cu;HM(+-f~fyBs9<^pP&06Qc3pA?gc240r%`Rej63m31GF6vH z3dP);+uX_sY{j;|f&4T=`DV8I^(9+H<1~6MW3&9r6|CR}uN6My0YNF>y)WKxs zVFSvQ{r^e0SxQ;*dK(jiRHJmUyEOKxcHO8wiDrd=Giv9r_;8;o%fRumLag0rfN&vJu zjzAj1cJ?s|3mvJ7J~sH7wV%(AmC%dACmK%EYg;eHN(sF-J^(iC7N+*vzWoi*qOy8O zWfQA+x|oU!tnq~}Z5X%iHd*hM&w4~RkV%&=sCXudu4^b>&?k&c1t@(96|Jn>%o3u|XFx#;N)>O1b z1@z;M*+E`~a=$%VsA4Jg(R=K`@0tQp_H#W*$Kt&tYW9xDU}UT_NYX0Bg7O#}=-eQz z`1`3BT7NErT(kZn^H~3Q1nFb_7o+id`U@~oR&Y*XB&VqwRNu}P3WaC=ayDj~blzQG z;L0--GxHm3fOv_`H8ubjYl59GWF&3hjrnQc%Y0$>k(>5*7dvLkj(?>M_-T$&;)6CR z(4WF1$P=kZj>M92&{Z*)eMMQ~k$j?JK3Yhx97ukW)-z`;Go|6Y4Yuv|#b~6Y^pn6m zj7ZKH)=6^M=@ROUD9)!O)o>I#)eAz%CYPHom*Zltn%w) zERnKu-wjYaFS-b_dyqZAge=p8NwEo}kWo?A0wj|h81o}f5hzg3$4CSY<&9xJfecPT z{ZFT4mneLaDI3i(uZPUkotee*-aw6_Vh2xM9wjOWAb^N#A^ zV6Kg*lQWus@%SiZJU0ZmH$VETHKbQ9(>5+!Ea zY_#+|iX6AI_V%y?`M{nDz?zx}BY+xy1PYDQMrrEtC~8!{b-~)#Qz))>PN?A$0uH8w z`&g^?Yr2gSyvkSo9_@H}YyRU(Qmr1HPMqEdL{OaRaB(6(lQvz2HmT69=+l6kt^7~tT zh@xe_PUsAugBfsx3mDHM%CMNu;nIt%hGk^N70oEgZ#pMNA{ao<-rZvA7(*_@7{6B~(Bejqx2_-a?vj9vy|t3KeETT1D z$$=la3udf^wrIxOr|FA!Y+l$>sGrPYVZrj^GHVPss=BRkxP&duVNDZU(0F2G+=qMd z3WaC|SP-x>5Mpxm^m(>QMj^3Wke;k&$bujPNb;eLilSMF3?p}#dXLmYaBn#JlvOcB zi&NW(5z!3nR*5&5Xy%gEu%Y$QNUj*>-rPMTi-+xp47mDjCMjI~wihzsu^+K)fdL!% znQ+=LaoKn1!Ln1MVFZV!2emY~Ougm?B>jUpsX-r_LR_)aODm~?B=q?v2_oh@up^D1BVjfK zAA_1_D8@Z|0YXyfKH_(~@)ga4VjS-(-l1u8i*M`1Xs#$(Dz^j=eHeawEbF6#DeQ4L zw8_zto7u>rSS2}j1OhsNbn?6rtS77O|x7iI{QH^py6Dw!6S!N411d~go)4vpOf)VTy5!E_(0 zt0zS%^wI}gF_Z4!hn)q+A0Mx`BUwuVpLvg9G|oAkz|$0Hjf6=&507uLYpL|XnyDE> zzEt|4Iw_@Wv=kASW9@Zr?%08M_Bu_D+yXLQ-Yiln$#MpqL`sy>SH6s!7Of>9$Qn8{ zwf0l6@gp`!A}N?QDm2;D9ySLx6{A4#um|9uHEOemrl5oB+Y zSRSd<+MU8yV^KqIQrMt&3YeBOHrR|~T1w+YyI~>E16P8Ti$0}T=?zOz@=IZIR6?wj zq=g}j-r(0Gze)bmv;l#`eKUn{rjG_53wy@3knuehg$+^+X8Y6u#9|lkRfzG5$lX8< zSp!w=00Nj@m;pmoT5{D8)q;Ik88#{kI}yxJ+HP;eD6u*9V!>(lam~mKN+r%Fwuv|Knr<^3|_nF-i*DlhmoajfzYf*1dKs0FkyY3YNTxAVi z8nJ=8h>YfmIzb{}z|ar3Dp00@@pyR-4)*b0df#DFyB%aEgK6&=mus6xoeAW%!>gz$ zFIozMrjU(%?saj!$!kzBHGVLbOP2}}O)$+SQVC<#uNX38p@-p%0#W6t}Wi9s;VOyZ|2+QYexV^1MoV%4`9n4jG9R=#&8`rKilc(kZhKCpPIRa~D~gr7HW= zjB6p7UL{i|HaXaYm@=?;m!yM!UNU8#lunuZ=S!!|em-p%_k&YrT0eKM8&xii2lnEYFn61TahehT)t3QN$qcp(UOvVyVR6T96O ztj$(ge0$weaX+;S1J5i4x14%7Y$VGYml2QEwvHiLauW$!y}QEaK@@5*JURCU0$_1P z0OBX-7N43In6a#G;LKJW{_p9+vJsso!h=Tv9veF{s~BEsJeThZDqH)r#lm#|*=iK5 zk)Ps9Ymrf1&--yGwR39$8aC~dvb-Nn^_8P^0)XqarD(Z=qLlTm3U4z>4)yz4)NixN z9Etsi)pFgO{1$OCQMD)Lu$&7(jiMlGr|Ey}O(aaoUgDZDQ|v<6g!R;{@gQaKR%4La z&I^lHlvTb`Vqz+-VOBtehz&;cI#n3fue%drICElTxk3NBC??y_R_~$EQ_(+;Iji(ywl6&&j7Z@Q<@BZp7aW2rc|RvkT=%P*@!cV za@!%TO_mI_%(z%Sk!tV6L#EESog@nB)Fw`N*?(UM~yFF_X~%4C4q zBWG-4URvwzb~ZF395dKi?zq92SfoV>2`L!I5Y~wAI6}f$G`uSnsN@QG+SL9se&*dE z`rT8=x3QrX+#!3{0&H@}BszvlWk80_%?!*RJurjyH#&e+O>pN}@hD}n%X=f2!M!nE8Wy5ei35J2Cscj&`Y3)0p>*9u{b0-s{+=NenjmG`LTYD6Vl zkaY(QE_XM3t&kPEEtE$r2BQ!Y#JhGl05hvmq|tD!fvy#Hr!^wwkD@p|E+GO8s*2qS zdXH%O8+PxAz>TP|N2}PrWN)=RixxK<u7~r+ zJTFf@jpjCL!Elejj&e83Iz>^U&ZB9?{az}1!4FB61t)=A*`0}W+p^KfIGNNii{|ZyF{qn2Zw7$^Sd89+{D7*F zs3^UHze|m)&}f}N%7Ae@5ZQ^nq3tz74VX83`LGO)n+_mi7n>kWlk)N{#>%`h#U;dD zRTK~v>OBm-SP48%)kq-K8@oRXQc3OUPcg+4EwB^^&Q28gd`M(tM0tevuS0h0l1xzG zq^IyW#Lj#)%mGxyrg_V~R&53UF8ajHypF;qEu8Md)NMGdTW-i1e_VtseFmDt=(WE9 z*DppBcIL`4L+w;FuhW)|sv3@RZsHN~B((>;kr-*D_+*F&iA8WRWRt%#2hGuTnwv#E zoyP2D>C4BGxWL7LUE{VmBo{Yc`C)D=-Cm3lyOY;aL?9mYb6{N=^TX6#kNb%FV)P-N zMTHIkhDS0&?Z1Ut;BS6mIentyZa4 zTxP=CEE5UMf^#DVNG#|BG3-yQ$-ob#>|VRl;_0a_&9;yR(I?^(vDW0h5R9|gYdX9b zX@HdnOoY(aY%CPP*k|qZ@lvR z502-_DDxB4`&(Eik%zE7D~o^8e+;Rz^F4Vg7gMd1>5AFOo$?9-s; zNO#}hQXy3PI?&Mh99XN(4ZjUeFtQA6Q4YKZe;B{}-2^4l1*`|_ru7}XJA}7OiKAx}Z)W7Pu}=#j|63+E`HicRz-ZDksuK z#XC(EK}8cE4STNoBJl>^u9ZaCZYw70fz`pts!YqH$wDzZaAk{DmO1k1Lq5z;Jw97M zEbs0N4ota>@XR40HE|EXu%{55IJ*ftw4C9fleJkiT9=I$L>JkO5oJ4hOYIzm@=>iB zYX2PGWspyuF(5i&mNChflFzOaiQ&0oBIS3(*xVs30>vW^SBLpC#~onw@;Ho_c<}5h zih)I^dH{|GAy&{#7aHQ=tyz_8TKjONzL=kSayhZssMXn3B_5MIi8EwR;t)d8kHl4< zeU6t!jP>q|^B!|DiR>=rL5TT4+$kX5pQ;Yl2$M@Xj#a-Is|>aQfr|NWwjsb$S%F zc+&Woean^C5Ku#x>`XAqdUMYx_tRX z`r%514i`Tr=~ef3p#k%@dSf9- z-$Ez|YGPgRjU27Q+=o&CK*oAFs+aUy+$~>s9x&;kfX5u%Y;YLMcx>^24a+Ns0~0qR z%7D!aE`F`3V8G<1P0(5njeU~|t^k>8bBZp?KW7(_RDeo~Exfu7w8CYHlNB+})eDLn zgG!9y0zB;n#f!!&jZ9Rg0i##kY69)v+q_TPtRRDh#lsebmye6`nSXQHZlVnbXtZ%n zt|ZQIK@x`$l71F$UDsGxn2ujCjq*+?8@;ysHQNc}yfa!41G%eI7EjEmVI8Qx4W>1_ zbz=pbwhzpa7r%#d?f=!_4Dn^&S*7WoPC#ub8m13inYm{M!p=j#*~qbSPzmuvt_lU4 zjx8YApsC*l1slhH9YO7ZwAB@)lVxh^xO&vE)tBf7N;w}>B9tUQ+HBcp^B`0Z_u5JuJqi$a#<#AoO zr<)R62bKU8+QdjYELd+yB?rj2eG(GC+tXcu3#z)&i%Hd2wapDwO&_Vni|Gh$Fb^!Y z!V}ZpXtPLQIhV;|BE+=6mPHyukK5ldDZrrJXeghXNb`#%zmQ;Z{wG5z8DNbR%}=x8 z?4336Ar(bCW1TC71a&v?_~xv=7s>cYo=KtSHTO&@Ivb6H zu?u|v-x|I>fCp17S|5|axh<_Nj;6++FGUIIk&!V1*8h{DV%q7%SH9FHp!&pdYfL|L z^SUtosKquo*bB*I;KKpIb!eC_t@6j=&Ys_r2{xanv^yEV_#O>fg>xQ7qCq`r3kspHk8=b2bECYAeZ7Ka_4tSZ@CB__VlSc7z(!|$e^+w>`bGlFsl-( zpNh`hjb=@EKrnA<$7sq0)%$QAaJu19CAMB*PUa<0m8be=ip817Cq)f4WDGW48_9?B z_Ql60!#Ne9lg-GL;wW=d#PDV`PCLknaby!}GW%=T#sF2%VJl?2ftuCR>Z&P2W8lt7 zD*l`^#{|GRng)1H2Kf&-m(05*z1tx{vl)|a$l(U!8TP=^l3m?q(qTzERuxnorLCfy zdEk0rc27WXu@RV!4W7ZK>$udo(0|6L@u~LN1|XC5#m=^+%=y6XVx{-RPo-U5b(igb=_6deGqpOdZ?cJg`Wi z5&c(z9B~6_OUEwL2b1TR(jekwvE@{r>0iL6w*L$!rs8ZAoG*#{gi$qF(2k8=BVqpa zNz)=Ws=~Yk5?$Y5r{xaLJp&``0KA}euBSP}H-s-*RFv(KDY$!PRwN-(UDr9uBmkg{ zC;t6;QI1fk)=mNXVvvRTLh1mRviM?R7&AQs9_T#hH{PR@lK7biZ=n zwFQb95KL9g6NPJXV}0TN$%A$`9@~KmZ_V3=Yp3Hzjc!GKYcG$W3ImDkNOc!hIvUeNpEm66^RBySQxRW*^OSDWa42i-ZUGXM`4Ze$z-a6{TI5Jz zJs1bGa>1heJ|{bxm$1q3rO8bfV171F1MD{4v%fDS?=eU`3)7eEP}g-2=8A<6k2`lF ziJQ=#-()a#tKTrU!Fhf}8ytSsuP!6hukO!{L-(yPX?m?~02lYy;RUki$AGcz-dA zq6_tm0p+VYa@OvXNkdpu?S(?#f8|6s0Jb8-Q;>7vse8 z2|xA+?Mv*QGjn`V9a=i;^gzkg#lt!LT=L5>U0UOHMPtz=tj$h9D!N{%6n91OP}aPz z7=AU>R_;~tY;#CCNwr%w#U6e;NDeQ89xBvmbyx-Gx!GlGGw;-X7s=!Sy*UbR<$~sV zdrfnrT(dfZIzWFo8(9jD;roKMB2y0G4Dy}eVBF4Uum|-_fyzs*6jM(dUd8#oO7yZEYSE0pPtbDt>CFRB@vG=tXJ31~l+Ed?#Qn(Zvd% zg9SMb^V=aaZm~j|?Tb<2QW(u`mYn+2#DYt{(Q_V1Di}T>KT;-{1Ye2EUVM!%(79j*0)lJi;+HKT&zP#7X!~7ThFri=78s8&72_>z z!081xNJh-Zd69}yfFJKOW3vY1MG?^oA!6pP^jB&+o6Qd#l~S=$X&)_2x;+e#>)$d% z^wO{x5L~VVUNTGF_|h3_hHuv0!Y^hmU(1=#LU=*4arSprL#K*feARXe$@cg8RfG6FF#}nQ0O|kSn1cyCez7$Sxb88-3RK|E-Eoa|aWgP&8T zDth^z=9{)=Slpsw&bt(bMf*d{RJdEVG`k-|=7xm%o~QIt&;sArEv;Y0=7dIuL^ zHk>AhWCMQPCWcpd1l_eiD&DO|&NUY&m|*Eir?3LcV%U^ve$!#JQl^Eb8HIgB{dBiH zd}xSekZUfyff4VqQQ-wuKgA*ePJXYAH{HU)NCtImYEP!(6qF+!J+zdXeXwmhcTNft zCbT~1V7NEAfboECnn7buM)Q5*bo zP?PfnctXptE(T7tcm_N2&|5b{aVfeUE#d>$GujAsm%OH0+_jWBAe`t3F6A$|%DThL z$kcYAFB@k2_IH5D*R?cp?xp?_nph{DL>gO@ zkO8qqYGV2?N#2JNeP8l6BlSa+`~WUwMi(4~E~AxeFuI1p?QFuAw3i+?pT{C}DZCQ* zsBm628@9~(U1lJi-)g0@n0o#iOpn{P#9L6wYQ*1+Y$wGB1<<`b0`!tM18mEimySpR zJjoPI*UGz~-mBFbJ6kmSH6Q&d2>;p&+ELhh{9}wgKq`RGn@poHswq*A1G_h~Q9x^= z*i9oxU1od!$E2TGrX#tshE(rW6gNjnu3Kh&M|e3E0@4OrL0cFrcU@uE%88*un5r5c z=%Kxm(7e=2TYag(VIh-G1rz zBmdg&3(YsD@ry4eqagft33GIXS53LKZT)iv9I>@|+Dpw1CnCceYKq@E6NUGWAXIzw zNimw;CE0gpqXD;*uOEoy>r{AyN3SW|{N9churNQ6*XVEQnGUm$cD{Z^{rnNW2gm*6 zF&$^{&H7wae}$Wq-B8pUf{GJZ>`=_DsC$6I;@0 z0}oe8W?B*Oolr;{dbb)S?I5o&zKy>DhUELAp(}j;^$?EXAcWSOoZyD~W^}b)+ItQo zEC9`k?X`W|+A|Rr7yDa~^eM0OuP>p)BGraHd5>mWEY0vb5YYEQ3#d_h1oU-#x3xFR zj0H;JxP>_GJE!Be`!0_Evd?!T&RK7;^aL%f`*5N8vU&3oBf(~}A35|G1x%4h6;Et` z;J*>goq|f%M0`G~WBSeX&qgOQneErG@ax<73Wp(Vjs?vFg~HQD5Ie6L__|ld{IKq& zaiM}3gM_-liF`CgT}@qnw`qY}PIYSsQ65^aZm@&PIA)o;!AbJWSxgY?;_5qn9kGkz zcFqEY@lY42TFmZ3bL;|@!K%!6$?+`>`c63%HoFmVt*~{{1?-&T`-?Ds^TvgD{hL8z zg7w3L-JYyOr3M^dD}t^blleFhH4TVPqhv|`d5|R^YiG4x;gv+Ae?-8v_Gc9`gPfhk z{0m46PsqH~ImTB4me|{lT`sFXS2j3nm z%jk#-I~SRv1Qua?J3N@r4{|iFndmDJw_$rl1ul3T8Zef;bJ1WS5`CkB--%RT9E%+1 zDk^Xt;;@#|jRFrtBw3pXLctYJ9by>Egc@fA#m@jSm#iX1wo1}esiW1fh=uJU&KP)F(HbV`^ z^OjTQJJio+L>n=i3{#)_OPkDGX}jP)fzr6M6I!T; zlYsu*Lx0roT!#yDV^6MPr8UYw97hB7d>&2>pITagw|l8sG{$xC3vVf?I{kQ7xdno% zV~LHlFvRW6!ubtst~43ut0^cyE)06?M|my`>CEC?8093ws3;L0N#)18eiG$V94ubg z=*q*xU8a4uJt(aD+*4sAQ!-2U>Nml-J-_-ewk(99m;432hm5ZO{3+c*epXaIXX<^I zR6jL3Y}7E@PuQQRX+dI-Tz+<{a%&XQ`oE${zX$`$gX z509Jeyp&|$44|btcPeEs)`-pH=G_4rcCLGwfWxTg5;#o#374-M_-Vi_sP3f4Rie~s zb{OL^3oE953XkCGw-Zx_RJV8js=l3=95|zbC2V+^3p8e#wT~XD)iFkz3*(7zsz_uF&RA~Uh@$({S7K=Pn{B_V!uFel@Eo8 zzcfB%r|aH?Z{=Vq#YV$tg0pW^I0kWWnbA8Xe)OyJ!G+g8!umH1goCg({WP%3w?fxn z8sB!x-H1@n*WnuWQUj=Nv(+GCE)*S!(awy5tNLLj@RDC$1dj7v4;oe%_$PdcnugVd z{>owm-xhWRxBze3!zTzH(~cRzj=O{}qT`@N;F(+!0G?oRaB7MyhUp10{8@&q{kF{z0SlYM!u(fsjC~NojQO*V)BTLPNQzeGNGA6=u#=%RaX2H)h z2+CsQf7e_ma?Ho2Psp=th}Rxk??+4(g{(&8p*jXxHXY^QB={4_+O7dSq* z=V*Q{WlKo4%`WJ`E)QxfjZ?TPZY%4XhO_dnfKHs#q${TKsenq@dV#eYd z4}1ewiRr4;XjN*i`Vxk!Ro?iO@1vcQTqx`EJ<&@q45r4@w2X`t{hl(ZY z!ljh1@F|LdFo0XLk|Er#buskxn8v~9wbIuUi2kNyll@PImZ1i^oLt@$YkP8GPp#@x z$tC?0*Yjj6lc8nW{7sLM;l1U$knDdlvsGpCSsHQPln1+BehVbR>@CaB9j#-LuHyl(yk5)DBzZfvWHsbkFi317M1Py{%k2 zl$W?gu?OX$UUz4LnY&Rh+L!f?UTPQlj+#V2@ZA=tr*-@r}ab~n|uy2|#gFmcc=O&dnK_@gh!6el=L8Wv$!A&I(3NEE?3hvW&PRU;8XO*vfqI{ivRYtQar&oP( zt!kAwzIxtB?S`bisV$MTAM3D!VSh4D5}2bK)N{&K%~2nYO&m!Wqz-<6|&XqsC9G0SIjX-Y->YlEy9%8?-61b<;p^55$j@f; zS)|vpk&X54-TCOf+<4+wZS#VDK)V?m-$&eqqhVP*!$d$$H&9R5FdP*R7*ri- zy`8U(L`C*tAMPJsm>06JoL;RF05>YmFYuAi~}PVN}iKH`ru7J?@h2Huq&?yZvV9d=~7t zL+?k?Fy1z{wjG+Cp(B!*M>!9P*&l@=hb_`-jxlBzc1sdx(qtOWqRQ?Vb5SmI+wUex z8gs+D+l;MX+85#AnR zBu$l`jg>nZD|<3_sm#IHmpB)zInv!XxKs%9(|yP6bcKYteX8_m>Prdq)uEM9gnamzp)K7il$;Qi9uSo|A1ZS^^yN;6R)_YZ zhqm;Prpy`5mph_a9ifjNp)&iaGDjs}?4)FMgg$zN$~^{L<_TaZTj_^?%RKk{r5^cR z9mkIy$HtC6eDnAH)pbGjg?D(N=TT@x0PMmHEOyKo&r8_{7=>LU#eGAq>w5lW=bp@3 zYFSW~*VW)~-hRAFisJ_$%xyiq@hkLnMxcizMQ|Tq>VU8D^7Cx5fHRi}dKRI9?`&_x zQAa7{_xh@+7Y`+LzPlN(LAJ`9Mj^S~j{;+lJ6H$O8=E#NGanKoRz9<{c%~w=rx$xj ze1W7fsA=hWTUczbc*k%F6ocAV2AO|~H*;zHLI;X!#u>|e&*tih$3fGpLSeM84PUMx zWR5)gkPq`ykI&W*FUfB0z?9~sJBKvqeT1mar+}F_y9qD*YI!M$29I39!tL5D65y29ISQc6v0AKrdn%uhYJ>MPv7ksi%GqhO|y+k2Ea+hbOJw_A{Bg_)JmCxAPRK<@e;yk>mQ^&CcU zS5Sws7_GBqY(Np?nHw0mby{k$76dqrX|va1P&YmYQz{>_rKkepg8JpDFzt z*uSBnt3zuHH6Jmw-^BiHb!cU(e$1@>nRf@PBlM9Yl(KhDB^S%IowLNonYM3!nr+kC zYhk$)(DlFu?J0%EY7!g!bp*8srs>JhGLJbWm$HNzGHHTLnIADkSV$QQISR}}?^gX*a}U>0W_$)K_x z>^GyQ)h1IltQN(syel3}cWl8u<96_yJg0Xbt^;#r;fy;ilGsWV}GY_2V!z0H;K7u< zUZCOy9@9eM@yi8ZWbeS4%NehCa&_-85VIYdf+~DN56}`+&Z)E3fV6V^7Hyxr=y83kng{jw9ylFi?m>Xg1Jw4usJQMo>k9I@207;ZvrfI<-QL z>ct^I2R;%drQ@4NQ72EsVEPxU|8BHou9`u-~8*VsTX%i;3Jy zb6NRZ{)v`SgN6{X#Hu0KQqzW@r%LP_g8o8A4k^q2^vH0#=PL|%MCMIo!UvMhB+^%r zxkbwG1%qqmn!zym)*5T}1{^vGlUUcogZA0oAkS)9Ori2)dq44!cu)^8psG z!-B6X`0qsD2CY&ISh%ZY;!WlU#<&J!=$I`{GiRa6;V#EA2Sr4Qx=!DKX_ zytrh?kK<*`tfpXw6BZil-H0-G+NpVK{Y91ym~b zbAxt@CL|Nf)cJ{xKmx3gUH#0d5{NGE>M<6oanb z6*t`TQIA9|H-DF(!KzG`{Z#StA1fB=|00U6DzC>bzHdBHF&{0IY6{S0P6l1>ojG2X z995R}MPGk1v63YSARl+e$?4NCWI>O5kc>f=Q-T?e!u5WXW|7zQT=ruU6LrSZhcH!r za5Fnt?i0p%-;(r2ONZ6Yt_b+@DemMd9^WyKwa?nTRTXXQP!!hCYn2SumQ;U&@}x)c z*b5O{8|7m{60$mz3g{Az&}1Bm?vxIbL>0wGX;LMB7owe;#s`u(6Y65k_IZI+{N=fP z-`b$eoDRx7!Wyjf3@aWEeIJv~RkNwgQ>>tiKE@i9JjWW8KFC_;N!D_YvX*<673ycn z!>qw*>C>!bA7?H5(BldZw3<$r8@qC&R&Kn?j+7ZAN6~US$PyD@>CUmtu5qe#$N0r| zi>qG{!+_oS)qO!MUo8287#dV^kD}xvMd?k7GFK_e+@<(Zmnl{s?18La>A@a6i;;Y= z=jkmK4cDGo-$K+Q$5Bri zarlq*tO^BC?5hz9-xA}jKJE8WLZQsi;sRBPP|#~u38@g26$?Q*x$wmV1662aSHw$H zPMB+nKzSffgQjn{Mo(o=fMgaag4Z*0Pk1&IG$@W4 z_NQ@mxKohEAsZgXN#-@dAI9OXWj>v^QS8OZyj^%(ODbJ`Rz7;*r`v^Yyz={7eF*!V zXueKg-id&LnMNs1gLEGyZxM$}FRmg{63mV#2ztXiUW6%y7GLzmf!XNH)OmsDru_EKF@~vvEF?K`$1ZF%xzbAo^H#!WLl)Z273y@_ou3Z zHOI&+HZ7k5?l)HP%p-?I{!!hA@ts@4trU#2f$T&rm>&*15A=<*h2L*RRk4Hcf=xTuxsBUK?1NR#X*a1SY4D! zzU9j6Y%$Efx`QJW0Jo+b*?1z_a{`HVKMQS=TX(REe{9M`P(1!zOiT*s8_^*q(Ug)L zrA=`zCy-TBW@ny224{^)B#GRJ3F&$%oiYE01Tta?Heh$-S}%~&8uMc&WwJ?u znUyJImrTnflCM~9PW5PqotSaTszZDyGiGMlsmXLc$lUaVV7T58EV5@5~eHNrd^P?zytpr|Ek)%vbOG#I5R$@~5An8s4lb(}hrzA3$&d9P8vg~{; zI~~i;#Q|SU)UU3?nW+M_gEDjmElcR^ z=*yxAKcUfQ^#OKKtd@H>0S?>4)Vm4F3`Q9PTp9aY7x^G%C{0=4N;T_Jy}Ha^yPQs4 zMx*}RjdrQvaGb54Qf4OqB9;!pdOs4g`ek%nmHT!qF{`h|0Du43cPHpFVde)Xh=2|1 z;$VZ~ApWZgY7b1qlOY`17_|L$I`KDPERK8P>HMxYIs|e5T;CXlbecllZxm$}A;0z3 z|4FErs>r@9#8h=jl#Ho!hQ#Sq@?{GI%>6i;6Y9`xG-qrBCNogj!A3JmP-8Q|mB&bIJ8&&c4?!z?LVt|ngEf0or~`TP zBygPSOf*t0WyGlQ0eO-pS(c>v=}=$IgwpY#t?jn-7la|1#mJ`P;9J)W;hb4bg0VeK zg4U3x!(%LHsiFA>f=V0o36KnxFt%r3aZ80;$&uYMl)u+YEEWk)*2I3kAHvnY$|vr& zAnzsE^KzPxE^vTn-Xr%0H(?(CvPm0gitP69@K$ttMnIFQaU2#xq_cU%nZey=Tz`&n zVDm!MlS%Xq@fRkll2c3bsLRsSudd?KO#j9&f(tUUdWE5>NfjSs`2(}bN6}sYJHk#V( zXoGhI=J%CrhRrKZoOi{b(gw)^$xtb``xTVxafnT<$u@OzX|~AJ3T?4d$%WctfAo57 z)Bk`&gYJMD;FUR6KX~5Z_zUzA64qikq81IQ8*IkYsI-4e8g=E1b_k@ge2$_F);w*C z5-i85@VsKuN*>LIR5)kCubru}0F6I*E^R60$P#ue<;60LI91ApUxWpvudA=xiN%bJ znjLF1xMpm9e;MlsvXxrLSXLPe8PVmeWW<-Tlo9>8)-smi!K%1P3zq7481rvf+>~L- zGW=MM8Ow5FIX3(fJh&=u?CPRgjZDfP5I0QIIEC8-+ot?SdbZ6+Gr_h6^CeC*xe;2} zv2!t6a5uh#?F-TTwq1+(F-iD48_hTJ$3q1#rf|0TVyfhfHO}>MKE6;Toay6b6btd& zEynj)RJ-lDIA;af0smqbKH=NYwFobfyW#35d}{{~z^>svP*B|s@YA@p zsq|hf(l=}(ad1DT7ki3kAJ>e``P3`UE9D_Zqd2&Q*JAEl;T74_e54@FU?>$_S)#0Wq!@G0DM~R>K zOC?xIe*@^n>j$dbl4v~m4ny=(>{0MYv4ZDEr-#i>C4q-d9olW9!}Fx9<03Z}1Kch0Adhh@hmX*X zxEwD-pSf^k9z`-13#t1c(lEmgw)3%|%nuqhe=yi%`t@)_X6wFVnV86;K(x=XzSq&-R~-&CU)FPmV-zTiiHCH@m=?0@t>H==#DYheaHiX3!+@ zv0PkBv0yxFA@tJjn6h6L*Etkqww)b7f+@Q`!W+XYi;N`%=5D;=#R(&Qha;K+EE~hm zSIE`bRLjnzvD*#Kr9}`uo3?K{(h`^m3-|+@*p|ysEvys!4cfy75IK{uZR%L4Sn5F< z&+281tDYv>nj73JCd8DX>qxosZMUt*_+Vq%E9zbbBiM~Is;JXwYz%W-2_RxHPd zUxo=+#f?>WoumFJKH|jRR-!5w(gvUDWtb6XC(5U@^)aaXN6e zJqXU_yMoHretb=Dy8mpo)-P^q^pk_18vFFnPo+lwvj)DZwSTElnC(B+l0%Dwy{-eI zE$-oCA`XJ!4fM?xP`q;AwFT;!7-UrmPZX{N!4j1J`zH@>(7p;^Ab;WQJ=u)bijrjt z93>;Hy*#2!7R|4hY?Vz%&pjAq#rMwS2cf?SRAJYb1>MivFh@25*_o5Vm-$OfMw;(o7HiJ<0SXDk79lYY?zwit!XR z)C4a-J5{+=J{51Hq2vSlZ3s@??GJ^e+iqh05?L9uG-hRxBu(TrjT0nJQ#eiF6n#r{ zk`j%iR39m$jg;ylpRI|k&S5htzVsaS7OwQ*r^miz=u1bwWZ*w*+<%F)-7Q>hQTqgs zunO|2>v=y8rB7370UAarijo4&&o_dKchYJuVrLYzKe1--tOy$Q!|tKEX#Qw285NcJ zB#K7V#Em|@B7L$D`3IDe;c(*BqeL}lpCpS4PKNd>Y>Xe(tFVIV2;1T)@!?c6g@J9T z1e3PSs%Xh1A~Y3yzNE@T7n65*BWJ7pt=A z0?!9Ibi3Jp2QS#RV|f>zzGQUUy6(YTvGCz>=T0X0(a@VbctyVC!}2WXMj@LnZ~M~} zregF+3ez*1LIe|yNlbb%Kx}$F0IFn30IqaZ0J3CZ0PeHa2IMC=Qh$O+3s4tDs8`(| zhf=AisWpsJ6eR_kpKk;ePvg&#lIEQcN!eqVI4OP1`yNvAN3NwO$yM==Vl{~~7u1uu z4-M{201*Jw3FCLaG9YDTQM!(0hc4BYpD$ghbSfvG%1WrRG75XGvQnzPq;4A!<@;+kOuYoZ5&JgaBNAZ77ZW02W?3q{+5 zxXM=`jfEjy6D!p66ZKY^LioGw?nD?)-nCXdi~q`b$h6Y%kn)YenLew&VsM6s#E)o$ z!>{_)WrX_G{kd__M6B(!38$*2t+1f|1fP;Axda7H_)72AsjT2&s2{`;umdFiSXSux zQ&B|}6B)39ZxQ!R$PG~W+hHt~A7l;n3nN*EQNJfY>^?}C$!8+~|r`eih=&eiK4QtT261#v&yaj9LT23&{8tXL*$33xdm*R zk*KJ9tS)>oK(gbw?Xr0A!*_;t!0p6ai{d*{4bb!U@_oZ$gC>NF!=%L~m=AE6=D}Mm z-MFpeVc@Mt0a2koiIjIFC(q2704Y=HelDb?I2zz~8`2yg1mb2{u?(y=8@Q;{fm`|- zS?b8G^zztL>d@_TuZ)?NyWd2Ah%JxM?sUktYe^=kL-=koJPxrl9}QFQQUpFGXfAZw z-RIi((V{=TTdYmfmza~QogOl`vTi_wJDF62IH?Nl_s z(L_n3s)nPSvv;tSPg0k|Zg?tb2`!M}$AGP`a_L8v^kYVyHN8a${vYL2Mr&h zaqsNxcrJRRns*RX+>VMy07>rkZ=$)~S`JQl=cCuPaS+$v==;OSD_@P*ih1^%*e#Z%s2dK4>oobtyQ#*O@KmrfoJg2<0c6pGZ>Z;H=I* zpES$)OI{$B9{ZA^FCF=kf&YwgU#^`i;B~-%hs;LXor?4C!oqByTaas^mlKw3e8z?g z`q`axh&!OPpo^Pmt$vty>U`BJF|Q$O>Y$4g5G++MvuPsOh(h#iQN|6Y|X7`@u}0bu08d|vp+i%Gc!3W6Ejk0 zqyKF$|D#@b`XT=CT;elc@%OuAd6qR-7Gm+ql4~Mp$p=ehLb25w<9yo!bhV?nwW)6^ zHSfbTufXgg?S=yLqRW<{!el2ltF_~U52A^>eUsz+Yu`ophR1Qwuk!M2aqtkS7Ta)Q zn_&D*r1vnS_Y`FM@yDt&{c|B6hCLq7gENka=j?2$zT8+wf}RTM2z#K2mjSEB5d^B!&F!Kyw@T0L`Khn7G4W>zi<& zpg%*Wp#ImM;)Pc38S&U6((8t^a0!Ulc>JvHPR`(Rcc5qwKUbmQZA@dqQL==)@>p`z zx!`h3xVX>}=M@ZoLLMn3pnw(wA#LQ3^?x%c=@73p11>C~+2IY-ZL_zret9UTa79vC ze|wrb-T5~*_WkNjsJ{SaBkdJKF38%0r2nOJG zL3E;-y&&tLe_#FX#?&!U}9gMwSchFbXlBd7=TD zR-@c$lzR+8o(-d1G$P1kqhbSGSk5>rFjwYl=zfsL;e+5U`wCDxs4Miq4PQ>Jg0;?OGwh#BI8w{Fh91J{z zK@atj4(dWoMFr49U5F{th2o0tdN`!Jx@QqSf@pPL+2;$bi(wMFsf*#dfz%u}ar>h= zp`*G5`!zgupOZ#_=a#;4J6CEi_(R$YcY|%Oy4p^4G3>8cfpytVnz__HX+NT+?o-Q8 z>K5?vLV~(aq%erh#I37~VZySSPhQhP3#APE^CN@pPAkI%n{P`__b@Tl&F4#;IMm91 zWJM%59e6h)sWKO9rpMKJn(mi+!}R-6l46Yx{=G>qzLt( za*$1YQ|X~-!=Bx`b=Lbb3S%evZjrswR3c?4W16%&iQsU32a zklEWkJjFHPMmBd#b^?tZ&$zJ8ldu9CPxNsyFAjD!Wdu>x(lfyxOx(faRTkEh@bi5q zP*e;Ruby^ni-XQrbv>KA$p*028>S_h0Tv0OWTbsV6-*7HG&Ihm1413!6Y1(fbaje- zJ`hbZr6Y>-04XV(k-&LOnT?Gzrp$&$OL1E}zBA+19 zrNSwuXjdQgkU6$~FJ_6na%Ve66|c<<0vyqVra(D6^*qwrcB3aYx$ zac>WNWD2!pMTual2BG%@Wt*Ct)DcJAexa2crG-{4Z|5k2#T)kQCfM)*!DwKsMxUV^ zm~7FYJmHt`ay$zBweS%(3?+~`{%9&6W}mlL2M2OShMjg>w8i72a^1KB`k4*y1YdwsGKr-jjeYRmjhT%uvLv=26FDD(E}awOxQV${4o@T z@g`#gd||JohtK6xPZ=EBLcS?qWHCDGM13`=dAe6+xmM=^rdtn3$c)<*$PV`?m(^A5YZ+^IbnV~V~lSBw8BeQbMrKTcP0jj;I;`@MA^7TOrGQuhU z<#Me5KQ4=-zoz4RmRPm{m2q-{c}v>|P089U>x%mtQ1@p1K&CTAru$ZT7Whj9uFB$-Te-v^>4UL5MsNiJ$1|L;^ zmI3g=Wa(jBh_^jp$2e?WJY`av;BkfMwllRjadJUbm)yAB2N(-n9)hd;lB-nhL47 z9s_0zif1py_sOf?trL+dN=uGS zv5;eZL*Sf5R*skXsm_5rF8Si<@3U@7j*Guui^CqTeZC?V=EOxZhIt@fwVqI2Ja&)C zgTtPz&1+pctJB+CK;6sdweu8@B1I*QANbWwLdW>tl=cUsIC@yJ(PeTJ(kSzBfc`3K z&{b;yj{g}qORn$*d;1GhM@+fYe3 zs#mTmfSae^`v}LrHCTh#>9G3@6%p7_vibMG`Np0>bm}z^@T+>?E)~VUkB6R#i@a7z z0J|}Y8R(JPZRSyzgfIN|mFl34;UUvnrLt!2qGjqt*3V;N8;W7K1NvlaaIC-pAmZsb zF8#3!;LEjFxGv+<$61^iVOrDgT47zqV)G|lcSlOcti87pAu3$cH8gE8khLfD#A*Fx zo+oo8ne_{ERtxzc0|iEP{&r{qCjMn@SFSWBD(&Y` z!&6K=!MtqC;5-%Kw(3VC=p4MBC~Q<0&Hmen(p3}ZroS8O4L<_lN@_`LZe3FK4&tQD z6fFZ0C~DTo77k1F&WchH5BJ!Z+A!9cWm;8A-MnupU|rb>!k31IkNl}n!cCg|?&(4& zJU!vB_gb9M=hW}+dEOJ)R^Gw~eErbHqF@<)EZ&cR%FfJcgO4MFFb#&a)aQ+ zC8K_s5`22mIOeL9F;_Xa=l6r+5!$@BnY4h!doNZD+Sqc0g*uWk3`>u8H4`Iy$+8;c2)=dA=n4{n_ z!`|M5fPMS}b`RgoD7Uk{d$FV$cG!7u&MWyw)sy^zugnlDXd|)B?c18r`8tX*d}h#6 z=TjSAE564SP_}Q~S+TumUxGvmy>|Nl_nmURyp?dyZdk8jk}T@8E#w+SoT+Mohj`S~ zM6cXFwW`3tW4d*p6z*6cvRW|;l5aq?V!{YW2v-wE02?kQa_?jq0gz-1g@0bKu|v=~ zvgNW-CfwK|%J*%WFXG+GNml%-zatrwO_qZGnpIGiHMs0Rcx@BSP-@uo89pA#D<3hF p1I#39Op8e4s4-Q(8grS&7FzR}3|8Ks5wrTh1g$ attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 + +This visualization code can be executed by Processing. + Download : http://www.processing.org/download/ + +The visualization code works with Processing version 1.5.1. From 90fdf35ae549b4a5ef3b0a8f47a9c23d76e9e485 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:59:20 +1000 Subject: [PATCH 44/89] GPL Licensed code has been removed --- .../attitude_estimator_so3_comp/README | 2 +- .../FreeIMU_cube/FreeIMU_cube.pde | 265 ------- .../FreeIMU_cube/LICENSE.txt | 674 ------------------ .../FreeIMU_cube/data/CourierNew36.vlw | Bin 114920 -> 0 bytes .../FreeIMU_yaw_pitch_roll.pde | 229 ------ .../FreeIMU_yaw_pitch_roll/LICENSE.txt | 674 ------------------ .../data/CourierNew36.vlw | Bin 114920 -> 0 bytes .../visualization_code/README | 9 - 8 files changed, 1 insertion(+), 1852 deletions(-) delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/README diff --git a/src/modules/attitude_estimator_so3_comp/README b/src/modules/attitude_estimator_so3_comp/README index 26b270d37c..79c50a5318 100644 --- a/src/modules/attitude_estimator_so3_comp/README +++ b/src/modules/attitude_estimator_so3_comp/README @@ -2,4 +2,4 @@ Synopsis nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 -Option -d is for debugging packet. See visualization_code folder. +Option -d is for debugging packet. See code for detailed packet structure. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde deleted file mode 100644 index 3706437d33..0000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde +++ /dev/null @@ -1,265 +0,0 @@ -/** -Visualize a cube which will assumes the orientation described -in a quaternion coming from the serial port. - -INSTRUCTIONS: -This program has to be run when you have the FreeIMU_serial -program running on your Arduino and the Arduino connected to your PC. -Remember to set the serialPort variable below to point to the name the -Arduino serial port has in your system. You can get the port using the -Arduino IDE from Tools->Serial Port: the selected entry is what you have -to use as serialPort variable. - - -Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ - -This program is free software: you can redistribute it and/or modify -it under the terms of the version 3 GNU General Public License as -published by the Free Software Foundation. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program. If not, see . - -*/ - -import processing.serial.*; -import processing.opengl.*; - -Serial myPort; // Create object from Serial class - -final String serialPort = "/dev/ttyUSB9"; // replace this with your serial port. On windows you will need something like "COM1". - -float [] q = new float [4]; -float [] hq = null; -float [] Euler = new float [3]; // psi, theta, phi - -int lf = 10; // 10 is '\n' in ASCII -byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) - -PFont font; -final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; - -final int burst = 32; -int count = 0; - -void myDelay(int time) { - try { - Thread.sleep(time); - } catch (InterruptedException e) { } -} - -void setup() -{ - size(VIEW_SIZE_X, VIEW_SIZE_Y, OPENGL); - myPort = new Serial(this, serialPort, 115200); - - // The font must be located in the sketch's "data" directory to load successfully - font = loadFont("CourierNew36.vlw"); - - println("Waiting IMU.."); - - myPort.clear(); - - while (myPort.available() == 0) { - myPort.write("v"); - myDelay(1000); - } - println(myPort.readStringUntil('\n')); - myPort.write("q" + char(burst)); - myPort.bufferUntil('\n'); -} - - -float decodeFloat(String inString) { - byte [] inData = new byte[4]; - - if(inString.length() == 8) { - inData[0] = (byte) unhex(inString.substring(0, 2)); - inData[1] = (byte) unhex(inString.substring(2, 4)); - inData[2] = (byte) unhex(inString.substring(4, 6)); - inData[3] = (byte) unhex(inString.substring(6, 8)); - } - - int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); - return Float.intBitsToFloat(intbits); -} - -void serialEvent(Serial p) { - if(p.available() >= 18) { - String inputString = p.readStringUntil('\n'); - //print(inputString); - if (inputString != null && inputString.length() > 0) { - String [] inputStringArr = split(inputString, ","); - if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements - q[0] = decodeFloat(inputStringArr[0]); - q[1] = decodeFloat(inputStringArr[1]); - q[2] = decodeFloat(inputStringArr[2]); - q[3] = decodeFloat(inputStringArr[3]); - } - } - count = count + 1; - if(burst == count) { // ask more data when burst completed - p.write("q" + char(burst)); - count = 0; - } - } -} - - - -void buildBoxShape() { - //box(60, 10, 40); - noStroke(); - beginShape(QUADS); - - //Z+ (to the drawing area) - fill(#00ff00); - vertex(-30, -5, 20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - //Z- - fill(#0000ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, 5, -20); - vertex(-30, 5, -20); - - //X- - fill(#ff0000); - vertex(-30, -5, -20); - vertex(-30, -5, 20); - vertex(-30, 5, 20); - vertex(-30, 5, -20); - - //X+ - fill(#ffff00); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(30, 5, -20); - - //Y- - fill(#ff00ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(-30, -5, 20); - - //Y+ - fill(#00ffff); - vertex(-30, 5, -20); - vertex(30, 5, -20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - endShape(); -} - - -void drawCube() { - pushMatrix(); - translate(VIEW_SIZE_X/2, VIEW_SIZE_Y/2 + 50, 0); - scale(5,5,5); - - // a demonstration of the following is at - // http://www.varesano.net/blog/fabio/ahrs-sensor-fusion-orientation-filter-3d-graphical-rotating-cube - rotateZ(-Euler[2]); - rotateX(-Euler[1]); - rotateY(-Euler[0]); - - buildBoxShape(); - - popMatrix(); -} - - -void draw() { - background(#000000); - fill(#ffffff); - - if(hq != null) { // use home quaternion - quaternionToEuler(quatProd(hq, q), Euler); - text("Disable home position by pressing \"n\"", 20, VIEW_SIZE_Y - 30); - } - else { - quaternionToEuler(q, Euler); - text("Point FreeIMU's X axis to your monitor then press \"h\"", 20, VIEW_SIZE_Y - 30); - } - - textFont(font, 20); - textAlign(LEFT, TOP); - text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 20); - text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 20); - - drawCube(); - //myPort.write("q" + 1); -} - - -void keyPressed() { - if(key == 'h') { - println("pressed h"); - - // set hq the home quaternion as the quatnion conjugate coming from the sensor fusion - hq = quatConjugate(q); - - } - else if(key == 'n') { - println("pressed n"); - hq = null; - } -} - -// See Sebastian O.H. Madwick report -// "An efficient orientation filter for inertial and intertial/magnetic sensor arrays" Chapter 2 Quaternion representation - -void quaternionToEuler(float [] q, float [] euler) { - euler[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); // psi - euler[1] = -asin(2 * q[1] * q[3] + 2 * q[0] * q[2]); // theta - euler[2] = atan2(2 * q[2] * q[3] - 2 * q[0] * q[1], 2 * q[0] * q[0] + 2 * q[3] * q[3] - 1); // phi -} - -float [] quatProd(float [] a, float [] b) { - float [] q = new float[4]; - - q[0] = a[0] * b[0] - a[1] * b[1] - a[2] * b[2] - a[3] * b[3]; - q[1] = a[0] * b[1] + a[1] * b[0] + a[2] * b[3] - a[3] * b[2]; - q[2] = a[0] * b[2] - a[1] * b[3] + a[2] * b[0] + a[3] * b[1]; - q[3] = a[0] * b[3] + a[1] * b[2] - a[2] * b[1] + a[3] * b[0]; - - return q; -} - -// returns a quaternion from an axis angle representation -float [] quatAxisAngle(float [] axis, float angle) { - float [] q = new float[4]; - - float halfAngle = angle / 2.0; - float sinHalfAngle = sin(halfAngle); - q[0] = cos(halfAngle); - q[1] = -axis[0] * sinHalfAngle; - q[2] = -axis[1] * sinHalfAngle; - q[3] = -axis[2] * sinHalfAngle; - - return q; -} - -// return the quaternion conjugate of quat -float [] quatConjugate(float [] quat) { - float [] conj = new float[4]; - - conj[0] = quat[0]; - conj[1] = -quat[1]; - conj[2] = -quat[2]; - conj[3] = -quat[3]; - - return conj; -} - diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt deleted file mode 100644 index 94a9ed024d..0000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw deleted file mode 100644 index 904771486a1a6d241fb5184282eb99780f730615..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 114920 zcmeFa4{%l6_aAiL{l%ElG%aF^6jR<0`9(}4QW23KrYS8_M8uR9DMiYU(niFXrV*tS zX@}7hD*SK3{~yKw@5le&iT_`>{z~f- z&vb;%`2XGb|6TYez83#~2mT3vAO1Jse=YtQNB^(kpTIim@bAZE7y4A(XVm! z@c-Rj9Q|76-w!|A!mzeQ+qo6EjreDnar|F{f5Jb2|8!i1!~{VD+~0@)-;00Er}h0I z;MhiO=iddtwzCm_wnghBO-M_^KZt*p!E#w=*HV+&^N&ewmtYr;RID=09rV{B|m>ca@3L zKKx@V#O*FqpO*QXh+|z!Px_Ufd*CPkDDN_kJWlw>@lRgnKl@Erp$Q)5(KymT;g7(x zT)t)-r!-?a?cX1T|L?&+c|mEdaeIMdTEigq1ZXI0h!*}o#_TiuT z*nf?KSKyz(FXMFF>DPSwZJeJ^l%zH7dJ+QyZm=V2Si@}x|U*8hx+E7$iH8&|HrKZ!Wb)pGfc*nF-&gcbf2 zJnVzcBl?vm{aT~{Y z$p=^A&%#5z-v=Fs6Tq`B%0=emKj#(UpTqxhvhF0}()o1W{yD^P4k<5jjFo1mtY7+$ zaV_9q`~F*qV;R~O=2Lln8h*+Kr8WK9hd&QL+pTn=U*QZq%jNqEh)d_wGXG+kd^(R> zZ9biwEJOSE&%@8Tpl$KndDiCBIOfwb{{tjFrPu{xv~A1Z5-=izv(Ki&s&`4 zW4xC6uh_Io7v@u1|Eo66_1%*%7i^r)Bj!{1EATMv$7z`tfoFN;%KWP~AM>XBa0xih zBkDnn-j!_N#N|%2fezuwaEb{>R{y)GaJitHO z&-xk1_UbzQZ@~WtERJ!Uzd8;N;U`UW9O&2j{!RGFf69Ywlg2%QpJ|nzbQS(Bc$VvX zAL3ZQ*2nhfIQ-l2vt6VU@%*RWLHKv@uXPdc*Y_A<>WaGdlMb5i--Vwv^y#Vf^#jj* zTJG=mcqyeLR^~G zTHgTT*iPjown^#v*Wv$z_~)9zw){blW`irl{U_^9pgZh~qrbeDrI+{{?=| zf1O9a&znbc!29(vo#y*r;ZOHZ`#!%y-2b*h+ydhK`smj(|96{Dd7gDEzx*F7#4WB6 z_kSXeb!eINYnlI-jZ>O2PWzsPpY`jw`(yimuMn48A@2V{9P7|B{rd7N#QndBV;gm? zqF-rNuyI-@(`X<5Kls^hon!QCzHo)O-(DfEh&Z-e%cNh+{9EvUkAKc(;x~AF#{EC# zyvF_hIPN>PcbPTdJC4;deEl8eA=h;Nvp#Qq_>Su==d-rcG>UXlI8OKo)z*@{xP4ng?!V-$_nS6O^D$2I zHNo$kKwb*>xPL`qc{F64Hjsxq~`i{WQ{;4eYdE!q2PugpoC+ENW)4(U%iLiz5j>5BC z|Nac(mdkg1g?xY3=2Jdp89GKMY(BP?G-KTw_vhdzuW3H^RpV$6VS3F+SL1#Qe%7J+ z{Q6D<&pI@pU*DexeiQzcKUtsB`iza!abVqA-(P^Ab!a~NHQ!%^pK?yemVV9G4nJj` z#?i0i{+HnA*l8U78rK0o>(Ds*HSRCN&pv4!{TlaI;3qxVFSeh43*TLYhvoP*(?0xF z;8{*Nnq2~(?bdwsYd-G7*>258zxMqy{L9t%*ATZ{eYX+k^91{0>&tMDKzUBtOg!tO z><47HM_4Xy0&z^I`8Yj_t4gb@)kVk&ho_fTvyl*okw(a{QBW1o&0e}knrp51NlgGsrAsM{x)N9yvh7*n~ppEwhx=h zW9c$Aj&0^R`SocW+r>C7lVxZe$DQrbxL=3g_F*%}kG!L0vJTDnhv5GW{Ie{!k!dY# z=DNvoQMpT3%ls|)ec9^wk20A&p=JJoSjXJ_7j2xjh3&R&`3>&-nNN9;e#@V~%`~h- z%cS4JZ!4{}Ocz((TgdfP-)Hp?Xta+CA%F98{QdBPzt0}?_u)PM_H^*~)G_`ZImF-n z4gB3u$=^(X%()<#h@y8vaA;xSpf@2YKe<@B4_d4!_T$r|{tS zVe|kV{N9Xi!GqsZ(Mfpl+Y+_FgWr7-xf8$D5r-eYnIhbPzpv>D2IMzrFK{_%D|DM+ z5G=6?!CWNC;mb&y%&(-Wjw0;X%&#E!MA1+Xm|sDF22apc`4z-*5HbkNuOQAwY`Xak zg7*2a2=ZpL=zk%cJ4-tF5C&~Rdd1DPv5+@Wv`2n-Ns(-M1hHp+1r)1ECAx0UqOL04h4bv6~s^!HGt|- zwAE(Gk}Cr9E2u)0hg*ndZGzxp*a2@xcuo;?FN9zb9}JIp7&P7sZSN)3=I>ehRQ9^Q zMN7w#P8eBnb3uSkg;yFfLG9UDU@`vhz|W?}FS3<$+6RQgqKD=;=lm zPv_rJfElPjH_&kzKEbR*3S^tmB$>V_y34{BuI{f4GWBhknprVi5@{fRAXrd8-LV~D z*TVJs&i+M&W*_d?+Ta4=g?<#GWaKUsys|+B3D*>JD9WF$sA$bcnr0vp zMrn-(ZIVJ%L0^UN6@4WLo8_#_aySalRaBfSxI%+#uG)hcpx%f1NK3V)9z3wlky%X(sTJ{UHpS@aZUeyE)i1HrHl( zdqAdoP`Sot0Nqo(0b<#-Hp!SsElm&iMifyb$FLO@`k39w5=Ak;oUmf6Bfx@FoIkrA z;kUt>5FLt6;kd#5j^apW3U|66w%1msMdHnt;R*rR$(a{^k zG(ud(5H7R@J11S3a{{YI=0x9QJ}ON1ZreH^6|S1a%Pd$oWRWrpQ*~6sWytXA=J)wl zHU)j647`MrFy$p5%`jR6N#Of49(Ds_(yhZRb+$(UOz~$&o!=+>) zW5VGC6<5O=uj$E-mywRt;>cz=^-+Fs9qtXdb;!y3vDS+C57vVkY+rB@2(;I=KiKp> zd*)2;{U+cj9mhBiUn5Z$+^y(FVIw>&mm{*4-6Y|OxDIy{+>9Hkgi9`@ zy4*UZ#(@&qh=NV*$^6)rts*(Mc8z6E3Uh%4qEY-u*$MtS z_)!0ZBWIxa1ahY4)PRHr&(xUW$l6iVZ)6dYdM&hQ8#I|3#dWf1b} zH5_y~%iz)M2vx<}k=#iJ1+IinIWh>dT-#VWD9j6eF5(in!h_s}xc3GfUcktBkXKm% z+!t(zEvlrqT^>EQuo+K-pc763oHPKp3ycL$pMr=viQr+B0}1pTPDL1n7(VJ#Lek!7 zRwU(IM12Gz;e|LdVUhDkL&Hcovh^*JzayzaDhVTv#F^skZ{s|fI)+znbrjq-C)Q08 z2>*j|;$U|wdRWv?mjDy)r3=6VX5Qw7q5D4ef|<#vNJ1!_gGQo$xRtX}NI9VZDRWKz zaH|)ioGLR!Uoq2FQ`F|7g=!7Jz3D4MBFttgz3AR3q6Ai`$BM0fx=*6$s2ARD=Z&H; zarUbpE<~v6AcDo9?DC>9@Xx$pfanH4oEJ8UF_-5P(Gs!!-gFpF-&5*dRW310q*Ypo zJdfnfaG&qWWOh7;2lM}Z6x}z)-{*b|%_W->s%9Z^K?@@^fVdDvz2jybkOU1;G!7}^ zR&R)0PD6>49|S%&oGuT7&+#ml{r6~((_Jad-=D^Qw*RE%nR>_!0~6Rz1i_9)4P*7$gLypz zmf{X#0_$iBf%NwBw(VBLUGF_7&2%N9m7z}7ED_6y9s)eKRX-1 z^0B&)$;khMBhjrxdSLY0n`r?kX{#s^)iQhhqHw+`{DvsK)^Zn(m4c0(3Q?mq`!XDbqR}H-wsEVCrsyGo$$CL}?_x1Ox46`E zP=;;Iz7Eoy3RD8xg4Udm_;3(et4}<5y@XyA=AYl%=a)(qG?odQL~6Kr5+#m3h|PT* zgoK-`iGy8Sh+J@UflGx8zKn8MFf|BM97oy)t7na>XM@*`=5Avfigsx=v2S!ekl-md zViFWl2%mwp08qSfjR25-0^#}_w@Og9jC(d-i?BhA1_4DGkNg%Fxk7meGprt>ICsvZ zu*FyhDLw(Q{nmI`n0#PI)T?C>^iH;8b~6x5NHTP4Lr{4NvT6*Rdva;4+0?rM3>|CL z#GOrZGPW-%j!e(1lBu^J`_t1)Mxe6HYOw5OFj;uLsS^95ZRa3L7uUV?T8_B=LCt*% zHw)vUqipKzpUM}*?3;TBSdfK=?tyHWAMG}BuHl*H;l>lvR)b=$rDQ2SICZ^`&cO8VZJs#MT3AyVXSm3vt<5)%H49$o3y0;scmkMZ()U*`2w{qxsE- zB?{eJf(;iiJI6C@+N{x%wr8X0EXHGrBSdJAqE}B~vo;}Ys6cl}j9C1FM!T(&&NNW- zv#?+nWZ6O(ZF?MGmSrzCLTDZyKvhjNNyl)P*>1bA-9c@;HIgsp-`=Q4q>KCU9+oMv z4a)dk&k)$-t&2!dU5J)2_zpVEuHA(pLY18wU$O4!Fc60Zygdmd(Ewz-DF#_r4B=-qMbrfZMAgZH@DpWrd@2&1&90hnT;)q<&FcqG=C!qtXMrlA{EMa|GY zmn{ELaq7c=s}k-E<~Zhag@$1RE`X3u`QS?T#MoRU$sMe7O(^tL3ufG!!!P08E5;qy zfLln{i6RVS4N=#1Jk1u13;peu5bG`v=Zo2=tvUjGb%pp~8oHAWH;`{effbNN3!UqO z%3~vFFy=4>;Jg`a8l|5G0a|j}cA^T2chCmogaT6E4bV-S0NZTv63-E=ren1IN_3Q4 zAHp6AxwROHtZk4Owb#%bl)F$HY`h{3gvDk(DvKe9thFy}c<#Kh0Ail>&4>BH^J{Lz zn+K_7Cu;HM(+-f~fyBs9<^pP&06Qc3pA?gc240r%`Rej63m31GF6vH z3dP);+uX_sY{j;|f&4T=`DV8I^(9+H<1~6MW3&9r6|CR}uN6My0YNF>y)WKxs zVFSvQ{r^e0SxQ;*dK(jiRHJmUyEOKxcHO8wiDrd=Giv9r_;8;o%fRumLag0rfN&vJu zjzAj1cJ?s|3mvJ7J~sH7wV%(AmC%dACmK%EYg;eHN(sF-J^(iC7N+*vzWoi*qOy8O zWfQA+x|oU!tnq~}Z5X%iHd*hM&w4~RkV%&=sCXudu4^b>&?k&c1t@(96|Jn>%o3u|XFx#;N)>O1b z1@z;M*+E`~a=$%VsA4Jg(R=K`@0tQp_H#W*$Kt&tYW9xDU}UT_NYX0Bg7O#}=-eQz z`1`3BT7NErT(kZn^H~3Q1nFb_7o+id`U@~oR&Y*XB&VqwRNu}P3WaC=ayDj~blzQG z;L0--GxHm3fOv_`H8ubjYl59GWF&3hjrnQc%Y0$>k(>5*7dvLkj(?>M_-T$&;)6CR z(4WF1$P=kZj>M92&{Z*)eMMQ~k$j?JK3Yhx97ukW)-z`;Go|6Y4Yuv|#b~6Y^pn6m zj7ZKH)=6^M=@ROUD9)!O)o>I#)eAz%CYPHom*Zltn%w) zERnKu-wjYaFS-b_dyqZAge=p8NwEo}kWo?A0wj|h81o}f5hzg3$4CSY<&9xJfecPT z{ZFT4mneLaDI3i(uZPUkotee*-aw6_Vh2xM9wjOWAb^N#A^ zV6Kg*lQWus@%SiZJU0ZmH$VETHKbQ9(>5+!Ea zY_#+|iX6AI_V%y?`M{nDz?zx}BY+xy1PYDQMrrEtC~8!{b-~)#Qz))>PN?A$0uH8w z`&g^?Yr2gSyvkSo9_@H}YyRU(Qmr1HPMqEdL{OaRaB(6(lQvz2HmT69=+l6kt^7~tT zh@xe_PUsAugBfsx3mDHM%CMNu;nIt%hGk^N70oEgZ#pMNA{ao<-rZvA7(*_@7{6B~(Bejqx2_-a?vj9vy|t3KeETT1D z$$=la3udf^wrIxOr|FA!Y+l$>sGrPYVZrj^GHVPss=BRkxP&duVNDZU(0F2G+=qMd z3WaC|SP-x>5Mpxm^m(>QMj^3Wke;k&$bujPNb;eLilSMF3?p}#dXLmYaBn#JlvOcB zi&NW(5z!3nR*5&5Xy%gEu%Y$QNUj*>-rPMTi-+xp47mDjCMjI~wihzsu^+K)fdL!% znQ+=LaoKn1!Ln1MVFZV!2emY~Ougm?B>jUpsX-r_LR_)aODm~?B=q?v2_oh@up^D1BVjfK zAA_1_D8@Z|0YXyfKH_(~@)ga4VjS-(-l1u8i*M`1Xs#$(Dz^j=eHeawEbF6#DeQ4L zw8_zto7u>rSS2}j1OhsNbn?6rtS77O|x7iI{QH^py6Dw!6S!N411d~go)4vpOf)VTy5!E_(0 zt0zS%^wI}gF_Z4!hn)q+A0Mx`BUwuVpLvg9G|oAkz|$0Hjf6=&507uLYpL|XnyDE> zzEt|4Iw_@Wv=kASW9@Zr?%08M_Bu_D+yXLQ-Yiln$#MpqL`sy>SH6s!7Of>9$Qn8{ zwf0l6@gp`!A}N?QDm2;D9ySLx6{A4#um|9uHEOemrl5oB+Y zSRSd<+MU8yV^KqIQrMt&3YeBOHrR|~T1w+YyI~>E16P8Ti$0}T=?zOz@=IZIR6?wj zq=g}j-r(0Gze)bmv;l#`eKUn{rjG_53wy@3knuehg$+^+X8Y6u#9|lkRfzG5$lX8< zSp!w=00Nj@m;pmoT5{D8)q;Ik88#{kI}yxJ+HP;eD6u*9V!>(lam~mKN+r%Fwuv|Knr<^3|_nF-i*DlhmoajfzYf*1dKs0FkyY3YNTxAVi z8nJ=8h>YfmIzb{}z|ar3Dp00@@pyR-4)*b0df#DFyB%aEgK6&=mus6xoeAW%!>gz$ zFIozMrjU(%?saj!$!kzBHGVLbOP2}}O)$+SQVC<#uNX38p@-p%0#W6t}Wi9s;VOyZ|2+QYexV^1MoV%4`9n4jG9R=#&8`rKilc(kZhKCpPIRa~D~gr7HW= zjB6p7UL{i|HaXaYm@=?;m!yM!UNU8#lunuZ=S!!|em-p%_k&YrT0eKM8&xii2lnEYFn61TahehT)t3QN$qcp(UOvVyVR6T96O ztj$(ge0$weaX+;S1J5i4x14%7Y$VGYml2QEwvHiLauW$!y}QEaK@@5*JURCU0$_1P z0OBX-7N43In6a#G;LKJW{_p9+vJsso!h=Tv9veF{s~BEsJeThZDqH)r#lm#|*=iK5 zk)Ps9Ymrf1&--yGwR39$8aC~dvb-Nn^_8P^0)XqarD(Z=qLlTm3U4z>4)yz4)NixN z9Etsi)pFgO{1$OCQMD)Lu$&7(jiMlGr|Ey}O(aaoUgDZDQ|v<6g!R;{@gQaKR%4La z&I^lHlvTb`Vqz+-VOBtehz&;cI#n3fue%drICElTxk3NBC??y_R_~$EQ_(+;Iji(ywl6&&j7Z@Q<@BZp7aW2rc|RvkT=%P*@!cV za@!%TO_mI_%(z%Sk!tV6L#EESog@nB)Fw`N*?(UM~yFF_X~%4C4q zBWG-4URvwzb~ZF395dKi?zq92SfoV>2`L!I5Y~wAI6}f$G`uSnsN@QG+SL9se&*dE z`rT8=x3QrX+#!3{0&H@}BszvlWk80_%?!*RJurjyH#&e+O>pN}@hD}n%X=f2!M!nE8Wy5ei35J2Cscj&`Y3)0p>*9u{b0-s{+=NenjmG`LTYD6Vl zkaY(QE_XM3t&kPEEtE$r2BQ!Y#JhGl05hvmq|tD!fvy#Hr!^wwkD@p|E+GO8s*2qS zdXH%O8+PxAz>TP|N2}PrWN)=RixxK<u7~r+ zJTFf@jpjCL!Elejj&e83Iz>^U&ZB9?{az}1!4FB61t)=A*`0}W+p^KfIGNNii{|ZyF{qn2Zw7$^Sd89+{D7*F zs3^UHze|m)&}f}N%7Ae@5ZQ^nq3tz74VX83`LGO)n+_mi7n>kWlk)N{#>%`h#U;dD zRTK~v>OBm-SP48%)kq-K8@oRXQc3OUPcg+4EwB^^&Q28gd`M(tM0tevuS0h0l1xzG zq^IyW#Lj#)%mGxyrg_V~R&53UF8ajHypF;qEu8Md)NMGdTW-i1e_VtseFmDt=(WE9 z*DppBcIL`4L+w;FuhW)|sv3@RZsHN~B((>;kr-*D_+*F&iA8WRWRt%#2hGuTnwv#E zoyP2D>C4BGxWL7LUE{VmBo{Yc`C)D=-Cm3lyOY;aL?9mYb6{N=^TX6#kNb%FV)P-N zMTHIkhDS0&?Z1Ut;BS6mIentyZa4 zTxP=CEE5UMf^#DVNG#|BG3-yQ$-ob#>|VRl;_0a_&9;yR(I?^(vDW0h5R9|gYdX9b zX@HdnOoY(aY%CPP*k|qZ@lvR z502-_DDxB4`&(Eik%zE7D~o^8e+;Rz^F4Vg7gMd1>5AFOo$?9-s; zNO#}hQXy3PI?&Mh99XN(4ZjUeFtQA6Q4YKZe;B{}-2^4l1*`|_ru7}XJA}7OiKAx}Z)W7Pu}=#j|63+E`HicRz-ZDksuK z#XC(EK}8cE4STNoBJl>^u9ZaCZYw70fz`pts!YqH$wDzZaAk{DmO1k1Lq5z;Jw97M zEbs0N4ota>@XR40HE|EXu%{55IJ*ftw4C9fleJkiT9=I$L>JkO5oJ4hOYIzm@=>iB zYX2PGWspyuF(5i&mNChflFzOaiQ&0oBIS3(*xVs30>vW^SBLpC#~onw@;Ho_c<}5h zih)I^dH{|GAy&{#7aHQ=tyz_8TKjONzL=kSayhZssMXn3B_5MIi8EwR;t)d8kHl4< zeU6t!jP>q|^B!|DiR>=rL5TT4+$kX5pQ;Yl2$M@Xj#a-Is|>aQfr|NWwjsb$S%F zc+&Woean^C5Ku#x>`XAqdUMYx_tRX z`r%514i`Tr=~ef3p#k%@dSf9- z-$Ez|YGPgRjU27Q+=o&CK*oAFs+aUy+$~>s9x&;kfX5u%Y;YLMcx>^24a+Ns0~0qR z%7D!aE`F`3V8G<1P0(5njeU~|t^k>8bBZp?KW7(_RDeo~Exfu7w8CYHlNB+})eDLn zgG!9y0zB;n#f!!&jZ9Rg0i##kY69)v+q_TPtRRDh#lsebmye6`nSXQHZlVnbXtZ%n zt|ZQIK@x`$l71F$UDsGxn2ujCjq*+?8@;ysHQNc}yfa!41G%eI7EjEmVI8Qx4W>1_ zbz=pbwhzpa7r%#d?f=!_4Dn^&S*7WoPC#ub8m13inYm{M!p=j#*~qbSPzmuvt_lU4 zjx8YApsC*l1slhH9YO7ZwAB@)lVxh^xO&vE)tBf7N;w}>B9tUQ+HBcp^B`0Z_u5JuJqi$a#<#AoO zr<)R62bKU8+QdjYELd+yB?rj2eG(GC+tXcu3#z)&i%Hd2wapDwO&_Vni|Gh$Fb^!Y z!V}ZpXtPLQIhV;|BE+=6mPHyukK5ldDZrrJXeghXNb`#%zmQ;Z{wG5z8DNbR%}=x8 z?4336Ar(bCW1TC71a&v?_~xv=7s>cYo=KtSHTO&@Ivb6H zu?u|v-x|I>fCp17S|5|axh<_Nj;6++FGUIIk&!V1*8h{DV%q7%SH9FHp!&pdYfL|L z^SUtosKquo*bB*I;KKpIb!eC_t@6j=&Ys_r2{xanv^yEV_#O>fg>xQ7qCq`r3kspHk8=b2bECYAeZ7Ka_4tSZ@CB__VlSc7z(!|$e^+w>`bGlFsl-( zpNh`hjb=@EKrnA<$7sq0)%$QAaJu19CAMB*PUa<0m8be=ip817Cq)f4WDGW48_9?B z_Ql60!#Ne9lg-GL;wW=d#PDV`PCLknaby!}GW%=T#sF2%VJl?2ftuCR>Z&P2W8lt7 zD*l`^#{|GRng)1H2Kf&-m(05*z1tx{vl)|a$l(U!8TP=^l3m?q(qTzERuxnorLCfy zdEk0rc27WXu@RV!4W7ZK>$udo(0|6L@u~LN1|XC5#m=^+%=y6XVx{-RPo-U5b(igb=_6deGqpOdZ?cJg`Wi z5&c(z9B~6_OUEwL2b1TR(jekwvE@{r>0iL6w*L$!rs8ZAoG*#{gi$qF(2k8=BVqpa zNz)=Ws=~Yk5?$Y5r{xaLJp&``0KA}euBSP}H-s-*RFv(KDY$!PRwN-(UDr9uBmkg{ zC;t6;QI1fk)=mNXVvvRTLh1mRviM?R7&AQs9_T#hH{PR@lK7biZ=n zwFQb95KL9g6NPJXV}0TN$%A$`9@~KmZ_V3=Yp3Hzjc!GKYcG$W3ImDkNOc!hIvUeNpEm66^RBySQxRW*^OSDWa42i-ZUGXM`4Ze$z-a6{TI5Jz zJs1bGa>1heJ|{bxm$1q3rO8bfV171F1MD{4v%fDS?=eU`3)7eEP}g-2=8A<6k2`lF ziJQ=#-()a#tKTrU!Fhf}8ytSsuP!6hukO!{L-(yPX?m?~02lYy;RUki$AGcz-dA zq6_tm0p+VYa@OvXNkdpu?S(?#f8|6s0Jb8-Q;>7vse8 z2|xA+?Mv*QGjn`V9a=i;^gzkg#lt!LT=L5>U0UOHMPtz=tj$h9D!N{%6n91OP}aPz z7=AU>R_;~tY;#CCNwr%w#U6e;NDeQ89xBvmbyx-Gx!GlGGw;-X7s=!Sy*UbR<$~sV zdrfnrT(dfZIzWFo8(9jD;roKMB2y0G4Dy}eVBF4Uum|-_fyzs*6jM(dUd8#oO7yZEYSE0pPtbDt>CFRB@vG=tXJ31~l+Ed?#Qn(Zvd% zg9SMb^V=aaZm~j|?Tb<2QW(u`mYn+2#DYt{(Q_V1Di}T>KT;-{1Ye2EUVM!%(79j*0)lJi;+HKT&zP#7X!~7ThFri=78s8&72_>z z!081xNJh-Zd69}yfFJKOW3vY1MG?^oA!6pP^jB&+o6Qd#l~S=$X&)_2x;+e#>)$d% z^wO{x5L~VVUNTGF_|h3_hHuv0!Y^hmU(1=#LU=*4arSprL#K*feARXe$@cg8RfG6FF#}nQ0O|kSn1cyCez7$Sxb88-3RK|E-Eoa|aWgP&8T zDth^z=9{)=Slpsw&bt(bMf*d{RJdEVG`k-|=7xm%o~QIt&;sArEv;Y0=7dIuL^ zHk>AhWCMQPCWcpd1l_eiD&DO|&NUY&m|*Eir?3LcV%U^ve$!#JQl^Eb8HIgB{dBiH zd}xSekZUfyff4VqQQ-wuKgA*ePJXYAH{HU)NCtImYEP!(6qF+!J+zdXeXwmhcTNft zCbT~1V7NEAfboECnn7buM)Q5*bo zP?PfnctXptE(T7tcm_N2&|5b{aVfeUE#d>$GujAsm%OH0+_jWBAe`t3F6A$|%DThL z$kcYAFB@k2_IH5D*R?cp?xp?_nph{DL>gO@ zkO8qqYGV2?N#2JNeP8l6BlSa+`~WUwMi(4~E~AxeFuI1p?QFuAw3i+?pT{C}DZCQ* zsBm628@9~(U1lJi-)g0@n0o#iOpn{P#9L6wYQ*1+Y$wGB1<<`b0`!tM18mEimySpR zJjoPI*UGz~-mBFbJ6kmSH6Q&d2>;p&+ELhh{9}wgKq`RGn@poHswq*A1G_h~Q9x^= z*i9oxU1od!$E2TGrX#tshE(rW6gNjnu3Kh&M|e3E0@4OrL0cFrcU@uE%88*un5r5c z=%Kxm(7e=2TYag(VIh-G1rz zBmdg&3(YsD@ry4eqagft33GIXS53LKZT)iv9I>@|+Dpw1CnCceYKq@E6NUGWAXIzw zNimw;CE0gpqXD;*uOEoy>r{AyN3SW|{N9churNQ6*XVEQnGUm$cD{Z^{rnNW2gm*6 zF&$^{&H7wae}$Wq-B8pUf{GJZ>`=_DsC$6I;@0 z0}oe8W?B*Oolr;{dbb)S?I5o&zKy>DhUELAp(}j;^$?EXAcWSOoZyD~W^}b)+ItQo zEC9`k?X`W|+A|Rr7yDa~^eM0OuP>p)BGraHd5>mWEY0vb5YYEQ3#d_h1oU-#x3xFR zj0H;JxP>_GJE!Be`!0_Evd?!T&RK7;^aL%f`*5N8vU&3oBf(~}A35|G1x%4h6;Et` z;J*>goq|f%M0`G~WBSeX&qgOQneErG@ax<73Wp(Vjs?vFg~HQD5Ie6L__|ld{IKq& zaiM}3gM_-liF`CgT}@qnw`qY}PIYSsQ65^aZm@&PIA)o;!AbJWSxgY?;_5qn9kGkz zcFqEY@lY42TFmZ3bL;|@!K%!6$?+`>`c63%HoFmVt*~{{1?-&T`-?Ds^TvgD{hL8z zg7w3L-JYyOr3M^dD}t^blleFhH4TVPqhv|`d5|R^YiG4x;gv+Ae?-8v_Gc9`gPfhk z{0m46PsqH~ImTB4me|{lT`sFXS2j3nm z%jk#-I~SRv1Qua?J3N@r4{|iFndmDJw_$rl1ul3T8Zef;bJ1WS5`CkB--%RT9E%+1 zDk^Xt;;@#|jRFrtBw3pXLctYJ9by>Egc@fA#m@jSm#iX1wo1}esiW1fh=uJU&KP)F(HbV`^ z^OjTQJJio+L>n=i3{#)_OPkDGX}jP)fzr6M6I!T; zlYsu*Lx0roT!#yDV^6MPr8UYw97hB7d>&2>pITagw|l8sG{$xC3vVf?I{kQ7xdno% zV~LHlFvRW6!ubtst~43ut0^cyE)06?M|my`>CEC?8093ws3;L0N#)18eiG$V94ubg z=*q*xU8a4uJt(aD+*4sAQ!-2U>Nml-J-_-ewk(99m;432hm5ZO{3+c*epXaIXX<^I zR6jL3Y}7E@PuQQRX+dI-Tz+<{a%&XQ`oE${zX$`$gX z509Jeyp&|$44|btcPeEs)`-pH=G_4rcCLGwfWxTg5;#o#374-M_-Vi_sP3f4Rie~s zb{OL^3oE953XkCGw-Zx_RJV8js=l3=95|zbC2V+^3p8e#wT~XD)iFkz3*(7zsz_uF&RA~Uh@$({S7K=Pn{B_V!uFel@Eo8 zzcfB%r|aH?Z{=Vq#YV$tg0pW^I0kWWnbA8Xe)OyJ!G+g8!umH1goCg({WP%3w?fxn z8sB!x-H1@n*WnuWQUj=Nv(+GCE)*S!(awy5tNLLj@RDC$1dj7v4;oe%_$PdcnugVd z{>owm-xhWRxBze3!zTzH(~cRzj=O{}qT`@N;F(+!0G?oRaB7MyhUp10{8@&q{kF{z0SlYM!u(fsjC~NojQO*V)BTLPNQzeGNGA6=u#=%RaX2H)h z2+CsQf7e_ma?Ho2Psp=th}Rxk??+4(g{(&8p*jXxHXY^QB={4_+O7dSq* z=V*Q{WlKo4%`WJ`E)QxfjZ?TPZY%4XhO_dnfKHs#q${TKsenq@dV#eYd z4}1ewiRr4;XjN*i`Vxk!Ro?iO@1vcQTqx`EJ<&@q45r4@w2X`t{hl(ZY z!ljh1@F|LdFo0XLk|Er#buskxn8v~9wbIuUi2kNyll@PImZ1i^oLt@$YkP8GPp#@x z$tC?0*Yjj6lc8nW{7sLM;l1U$knDdlvsGpCSsHQPln1+BehVbR>@CaB9j#-LuHyl(yk5)DBzZfvWHsbkFi317M1Py{%k2 zl$W?gu?OX$UUz4LnY&Rh+L!f?UTPQlj+#V2@ZA=tr*-@r}ab~n|uy2|#gFmcc=O&dnK_@gh!6el=L8Wv$!A&I(3NEE?3hvW&PRU;8XO*vfqI{ivRYtQar&oP( zt!kAwzIxtB?S`bisV$MTAM3D!VSh4D5}2bK)N{&K%~2nYO&m!Wqz-<6|&XqsC9G0SIjX-Y->YlEy9%8?-61b<;p^55$j@f; zS)|vpk&X54-TCOf+<4+wZS#VDK)V?m-$&eqqhVP*!$d$$H&9R5FdP*R7*ri- zy`8U(L`C*tAMPJsm>06JoL;RF05>YmFYuAi~}PVN}iKH`ru7J?@h2Huq&?yZvV9d=~7t zL+?k?Fy1z{wjG+Cp(B!*M>!9P*&l@=hb_`-jxlBzc1sdx(qtOWqRQ?Vb5SmI+wUex z8gs+D+l;MX+85#AnR zBu$l`jg>nZD|<3_sm#IHmpB)zInv!XxKs%9(|yP6bcKYteX8_m>Prdq)uEM9gnamzp)K7il$;Qi9uSo|A1ZS^^yN;6R)_YZ zhqm;Prpy`5mph_a9ifjNp)&iaGDjs}?4)FMgg$zN$~^{L<_TaZTj_^?%RKk{r5^cR z9mkIy$HtC6eDnAH)pbGjg?D(N=TT@x0PMmHEOyKo&r8_{7=>LU#eGAq>w5lW=bp@3 zYFSW~*VW)~-hRAFisJ_$%xyiq@hkLnMxcizMQ|Tq>VU8D^7Cx5fHRi}dKRI9?`&_x zQAa7{_xh@+7Y`+LzPlN(LAJ`9Mj^S~j{;+lJ6H$O8=E#NGanKoRz9<{c%~w=rx$xj ze1W7fsA=hWTUczbc*k%F6ocAV2AO|~H*;zHLI;X!#u>|e&*tih$3fGpLSeM84PUMx zWR5)gkPq`ykI&W*FUfB0z?9~sJBKvqeT1mar+}F_y9qD*YI!M$29I39!tL5D65y29ISQc6v0AKrdn%uhYJ>MPv7ksi%GqhO|y+k2Ea+hbOJw_A{Bg_)JmCxAPRK<@e;yk>mQ^&CcU zS5Sws7_GBqY(Np?nHw0mby{k$76dqrX|va1P&YmYQz{>_rKkepg8JpDFzt z*uSBnt3zuHH6Jmw-^BiHb!cU(e$1@>nRf@PBlM9Yl(KhDB^S%IowLNonYM3!nr+kC zYhk$)(DlFu?J0%EY7!g!bp*8srs>JhGLJbWm$HNzGHHTLnIADkSV$QQISR}}?^gX*a}U>0W_$)K_x z>^GyQ)h1IltQN(syel3}cWl8u<96_yJg0Xbt^;#r;fy;ilGsWV}GY_2V!z0H;K7u< zUZCOy9@9eM@yi8ZWbeS4%NehCa&_-85VIYdf+~DN56}`+&Z)E3fV6V^7Hyxr=y83kng{jw9ylFi?m>Xg1Jw4usJQMo>k9I@207;ZvrfI<-QL z>ct^I2R;%drQ@4NQ72EsVEPxU|8BHou9`u-~8*VsTX%i;3Jy zb6NRZ{)v`SgN6{X#Hu0KQqzW@r%LP_g8o8A4k^q2^vH0#=PL|%MCMIo!UvMhB+^%r zxkbwG1%qqmn!zym)*5T}1{^vGlUUcogZA0oAkS)9Ori2)dq44!cu)^8psG z!-B6X`0qsD2CY&ISh%ZY;!WlU#<&J!=$I`{GiRa6;V#EA2Sr4Qx=!DKX_ zytrh?kK<*`tfpXw6BZil-H0-G+NpVK{Y91ym~b zbAxt@CL|Nf)cJ{xKmx3gUH#0d5{NGE>M<6oanb z6*t`TQIA9|H-DF(!KzG`{Z#StA1fB=|00U6DzC>bzHdBHF&{0IY6{S0P6l1>ojG2X z995R}MPGk1v63YSARl+e$?4NCWI>O5kc>f=Q-T?e!u5WXW|7zQT=ruU6LrSZhcH!r za5Fnt?i0p%-;(r2ONZ6Yt_b+@DemMd9^WyKwa?nTRTXXQP!!hCYn2SumQ;U&@}x)c z*b5O{8|7m{60$mz3g{Az&}1Bm?vxIbL>0wGX;LMB7owe;#s`u(6Y65k_IZI+{N=fP z-`b$eoDRx7!Wyjf3@aWEeIJv~RkNwgQ>>tiKE@i9JjWW8KFC_;N!D_YvX*<673ycn z!>qw*>C>!bA7?H5(BldZw3<$r8@qC&R&Kn?j+7ZAN6~US$PyD@>CUmtu5qe#$N0r| zi>qG{!+_oS)qO!MUo8287#dV^kD}xvMd?k7GFK_e+@<(Zmnl{s?18La>A@a6i;;Y= z=jkmK4cDGo-$K+Q$5Bri zarlq*tO^BC?5hz9-xA}jKJE8WLZQsi;sRBPP|#~u38@g26$?Q*x$wmV1662aSHw$H zPMB+nKzSffgQjn{Mo(o=fMgaag4Z*0Pk1&IG$@W4 z_NQ@mxKohEAsZgXN#-@dAI9OXWj>v^QS8OZyj^%(ODbJ`Rz7;*r`v^Yyz={7eF*!V zXueKg-id&LnMNs1gLEGyZxM$}FRmg{63mV#2ztXiUW6%y7GLzmf!XNH)OmsDru_EKF@~vvEF?K`$1ZF%xzbAo^H#!WLl)Z273y@_ou3Z zHOI&+HZ7k5?l)HP%p-?I{!!hA@ts@4trU#2f$T&rm>&*15A=<*h2L*RRk4Hcf=xTuxsBUK?1NR#X*a1SY4D! zzU9j6Y%$Efx`QJW0Jo+b*?1z_a{`HVKMQS=TX(REe{9M`P(1!zOiT*s8_^*q(Ug)L zrA=`zCy-TBW@ny224{^)B#GRJ3F&$%oiYE01Tta?Heh$-S}%~&8uMc&WwJ?u znUyJImrTnflCM~9PW5PqotSaTszZDyGiGMlsmXLc$lUaVV7T58EV5@5~eHNrd^P?zytpr|Ek)%vbOG#I5R$@~5An8s4lb(}hrzA3$&d9P8vg~{; zI~~i;#Q|SU)UU3?nW+M_gEDjmElcR^ z=*yxAKcUfQ^#OKKtd@H>0S?>4)Vm4F3`Q9PTp9aY7x^G%C{0=4N;T_Jy}Ha^yPQs4 zMx*}RjdrQvaGb54Qf4OqB9;!pdOs4g`ek%nmHT!qF{`h|0Du43cPHpFVde)Xh=2|1 z;$VZ~ApWZgY7b1qlOY`17_|L$I`KDPERK8P>HMxYIs|e5T;CXlbecllZxm$}A;0z3 z|4FErs>r@9#8h=jl#Ho!hQ#Sq@?{GI%>6i;6Y9`xG-qrBCNogj!A3JmP-8Q|mB&bIJ8&&c4?!z?LVt|ngEf0or~`TP zBygPSOf*t0WyGlQ0eO-pS(c>v=}=$IgwpY#t?jn-7la|1#mJ`P;9J)W;hb4bg0VeK zg4U3x!(%LHsiFA>f=V0o36KnxFt%r3aZ80;$&uYMl)u+YEEWk)*2I3kAHvnY$|vr& zAnzsE^KzPxE^vTn-Xr%0H(?(CvPm0gitP69@K$ttMnIFQaU2#xq_cU%nZey=Tz`&n zVDm!MlS%Xq@fRkll2c3bsLRsSudd?KO#j9&f(tUUdWE5>NfjSs`2(}bN6}sYJHk#V( zXoGhI=J%CrhRrKZoOi{b(gw)^$xtb``xTVxafnT<$u@OzX|~AJ3T?4d$%WctfAo57 z)Bk`&gYJMD;FUR6KX~5Z_zUzA64qikq81IQ8*IkYsI-4e8g=E1b_k@ge2$_F);w*C z5-i85@VsKuN*>LIR5)kCubru}0F6I*E^R60$P#ue<;60LI91ApUxWpvudA=xiN%bJ znjLF1xMpm9e;MlsvXxrLSXLPe8PVmeWW<-Tlo9>8)-smi!K%1P3zq7481rvf+>~L- zGW=MM8Ow5FIX3(fJh&=u?CPRgjZDfP5I0QIIEC8-+ot?SdbZ6+Gr_h6^CeC*xe;2} zv2!t6a5uh#?F-TTwq1+(F-iD48_hTJ$3q1#rf|0TVyfhfHO}>MKE6;Toay6b6btd& zEynj)RJ-lDIA;af0smqbKH=NYwFobfyW#35d}{{~z^>svP*B|s@YA@p zsq|hf(l=}(ad1DT7ki3kAJ>e``P3`UE9D_Zqd2&Q*JAEl;T74_e54@FU?>$_S)#0Wq!@G0DM~R>K zOC?xIe*@^n>j$dbl4v~m4ny=(>{0MYv4ZDEr-#i>C4q-d9olW9!}Fx9<03Z}1Kch0Adhh@hmX*X zxEwD-pSf^k9z`-13#t1c(lEmgw)3%|%nuqhe=yi%`t@)_X6wFVnV86;K(x=XzSq&-R~-&CU)FPmV-zTiiHCH@m=?0@t>H==#DYheaHiX3!+@ zv0PkBv0yxFA@tJjn6h6L*Etkqww)b7f+@Q`!W+XYi;N`%=5D;=#R(&Qha;K+EE~hm zSIE`bRLjnzvD*#Kr9}`uo3?K{(h`^m3-|+@*p|ysEvys!4cfy75IK{uZR%L4Sn5F< z&+281tDYv>nj73JCd8DX>qxosZMUt*_+Vq%E9zbbBiM~Is;JXwYz%W-2_RxHPd zUxo=+#f?>WoumFJKH|jRR-!5w(gvUDWtb6XC(5U@^)aaXN6e zJqXU_yMoHretb=Dy8mpo)-P^q^pk_18vFFnPo+lwvj)DZwSTElnC(B+l0%Dwy{-eI zE$-oCA`XJ!4fM?xP`q;AwFT;!7-UrmPZX{N!4j1J`zH@>(7p;^Ab;WQJ=u)bijrjt z93>;Hy*#2!7R|4hY?Vz%&pjAq#rMwS2cf?SRAJYb1>MivFh@25*_o5Vm-$OfMw;(o7HiJ<0SXDk79lYY?zwit!XR z)C4a-J5{+=J{51Hq2vSlZ3s@??GJ^e+iqh05?L9uG-hRxBu(TrjT0nJQ#eiF6n#r{ zk`j%iR39m$jg;ylpRI|k&S5htzVsaS7OwQ*r^miz=u1bwWZ*w*+<%F)-7Q>hQTqgs zunO|2>v=y8rB7370UAarijo4&&o_dKchYJuVrLYzKe1--tOy$Q!|tKEX#Qw285NcJ zB#K7V#Em|@B7L$D`3IDe;c(*BqeL}lpCpS4PKNd>Y>Xe(tFVIV2;1T)@!?c6g@J9T z1e3PSs%Xh1A~Y3yzNE@T7n65*BWJ7pt=A z0?!9Ibi3Jp2QS#RV|f>zzGQUUy6(YTvGCz>=T0X0(a@VbctyVC!}2WXMj@LnZ~M~} zregF+3ez*1LIe|yNlbb%Kx}$F0IFn30IqaZ0J3CZ0PeHa2IMC=Qh$O+3s4tDs8`(| zhf=AisWpsJ6eR_kpKk;ePvg&#lIEQcN!eqVI4OP1`yNvAN3NwO$yM==Vl{~~7u1uu z4-M{201*Jw3FCLaG9YDTQM!(0hc4BYpD$ghbSfvG%1WrRG75XGvQnzPq;4A!<@;+kOuYoZ5&JgaBNAZ77ZW02W?3q{+5 zxXM=`jfEjy6D!p66ZKY^LioGw?nD?)-nCXdi~q`b$h6Y%kn)YenLew&VsM6s#E)o$ z!>{_)WrX_G{kd__M6B(!38$*2t+1f|1fP;Axda7H_)72AsjT2&s2{`;umdFiSXSux zQ&B|}6B)39ZxQ!R$PG~W+hHt~A7l;n3nN*EQNJfY>^?}C$!8+~|r`eih=&eiK4QtT261#v&yaj9LT23&{8tXL*$33xdm*R zk*KJ9tS)>oK(gbw?Xr0A!*_;t!0p6ai{d*{4bb!U@_oZ$gC>NF!=%L~m=AE6=D}Mm z-MFpeVc@Mt0a2koiIjIFC(q2704Y=HelDb?I2zz~8`2yg1mb2{u?(y=8@Q;{fm`|- zS?b8G^zztL>d@_TuZ)?NyWd2Ah%JxM?sUktYe^=kL-=koJPxrl9}QFQQUpFGXfAZw z-RIi((V{=TTdYmfmza~QogOl`vTi_wJDF62IH?Nl_s z(L_n3s)nPSvv;tSPg0k|Zg?tb2`!M}$AGP`a_L8v^kYVyHN8a${vYL2Mr&h zaqsNxcrJRRns*RX+>VMy07>rkZ=$)~S`JQl=cCuPaS+$v==;OSD_@P*ih1^%*e#Z%s2dK4>oobtyQ#*O@KmrfoJg2<0c6pGZ>Z;H=I* zpES$)OI{$B9{ZA^FCF=kf&YwgU#^`i;B~-%hs;LXor?4C!oqByTaas^mlKw3e8z?g z`q`axh&!OPpo^Pmt$vty>U`BJF|Q$O>Y$4g5G++MvuPsOh(h#iQN|6Y|X7`@u}0bu08d|vp+i%Gc!3W6Ejk0 zqyKF$|D#@b`XT=CT;elc@%OuAd6qR-7Gm+ql4~Mp$p=ehLb25w<9yo!bhV?nwW)6^ zHSfbTufXgg?S=yLqRW<{!el2ltF_~U52A^>eUsz+Yu`ophR1Qwuk!M2aqtkS7Ta)Q zn_&D*r1vnS_Y`FM@yDt&{c|B6hCLq7gENka=j?2$zT8+wf}RTM2z#K2mjSEB5d^B!&F!Kyw@T0L`Khn7G4W>zi<& zpg%*Wp#ImM;)Pc38S&U6((8t^a0!Ulc>JvHPR`(Rcc5qwKUbmQZA@dqQL==)@>p`z zx!`h3xVX>}=M@ZoLLMn3pnw(wA#LQ3^?x%c=@73p11>C~+2IY-ZL_zret9UTa79vC ze|wrb-T5~*_WkNjsJ{SaBkdJKF38%0r2nOJG zL3E;-y&&tLe_#FX#?&!U}9gMwSchFbXlBd7=TD zR-@c$lzR+8o(-d1G$P1kqhbSGSk5>rFjwYl=zfsL;e+5U`wCDxs4Miq4PQ>Jg0;?OGwh#BI8w{Fh91J{z zK@atj4(dWoMFr49U5F{th2o0tdN`!Jx@QqSf@pPL+2;$bi(wMFsf*#dfz%u}ar>h= zp`*G5`!zgupOZ#_=a#;4J6CEi_(R$YcY|%Oy4p^4G3>8cfpytVnz__HX+NT+?o-Q8 z>K5?vLV~(aq%erh#I37~VZySSPhQhP3#APE^CN@pPAkI%n{P`__b@Tl&F4#;IMm91 zWJM%59e6h)sWKO9rpMKJn(mi+!}R-6l46Yx{=G>qzLt( za*$1YQ|X~-!=Bx`b=Lbb3S%evZjrswR3c?4W16%&iQsU32a zklEWkJjFHPMmBd#b^?tZ&$zJ8ldu9CPxNsyFAjD!Wdu>x(lfyxOx(faRTkEh@bi5q zP*e;Ruby^ni-XQrbv>KA$p*028>S_h0Tv0OWTbsV6-*7HG&Ihm1413!6Y1(fbaje- zJ`hbZr6Y>-04XV(k-&LOnT?Gzrp$&$OL1E}zBA+19 zrNSwuXjdQgkU6$~FJ_6na%Ve66|c<<0vyqVra(D6^*qwrcB3aYx$ zac>WNWD2!pMTual2BG%@Wt*Ct)DcJAexa2crG-{4Z|5k2#T)kQCfM)*!DwKsMxUV^ zm~7FYJmHt`ay$zBweS%(3?+~`{%9&6W}mlL2M2OShMjg>w8i72a^1KB`k4*y1YdwsGKr-jjeYRmjhT%uvLv=26FDD(E}awOxQV${4o@T z@g`#gd||JohtK6xPZ=EBLcS?qWHCDGM13`=dAe6+xmM=^rdtn3$c)<*$PV`?m(^A5YZ+^IbnV~V~lSBw8BeQbMrKTcP0jj;I;`@MA^7TOrGQuhU z<#Me5KQ4=-zoz4RmRPm{m2q-{c}v>|P089U>x%mtQ1@p1K&CTAru$ZT7Whj9uFB$-Te-v^>4UL5MsNiJ$1|L;^ zmI3g=Wa(jBh_^jp$2e?WJY`av;BkfMwllRjadJUbm)yAB2N(-n9)hd;lB-nhL47 z9s_0zif1py_sOf?trL+dN=uGS zv5;eZL*Sf5R*skXsm_5rF8Si<@3U@7j*Guui^CqTeZC?V=EOxZhIt@fwVqI2Ja&)C zgTtPz&1+pctJB+CK;6sdweu8@B1I*QANbWwLdW>tl=cUsIC@yJ(PeTJ(kSzBfc`3K z&{b;yj{g}qORn$*d;1GhM@+fYe3 zs#mTmfSae^`v}LrHCTh#>9G3@6%p7_vibMG`Np0>bm}z^@T+>?E)~VUkB6R#i@a7z z0J|}Y8R(JPZRSyzgfIN|mFl34;UUvnrLt!2qGjqt*3V;N8;W7K1NvlaaIC-pAmZsb zF8#3!;LEjFxGv+<$61^iVOrDgT47zqV)G|lcSlOcti87pAu3$cH8gE8khLfD#A*Fx zo+oo8ne_{ERtxzc0|iEP{&r{qCjMn@SFSWBD(&Y` z!&6K=!MtqC;5-%Kw(3VC=p4MBC~Q<0&Hmen(p3}ZroS8O4L<_lN@_`LZe3FK4&tQD z6fFZ0C~DTo77k1F&WchH5BJ!Z+A!9cWm;8A-MnupU|rb>!k31IkNl}n!cCg|?&(4& zJU!vB_gb9M=hW}+dEOJ)R^Gw~eErbHqF@<)EZ&cR%FfJcgO4MFFb#&a)aQ+ zC8K_s5`22mIOeL9F;_Xa=l6r+5!$@BnY4h!doNZD+Sqc0g*uWk3`>u8H4`Iy$+8;c2)=dA=n4{n_ z!`|M5fPMS}b`RgoD7Uk{d$FV$cG!7u&MWyw)sy^zugnlDXd|)B?c18r`8tX*d}h#6 z=TjSAE564SP_}Q~S+TumUxGvmy>|Nl_nmURyp?dyZdk8jk}T@8E#w+SoT+Mohj`S~ zM6cXFwW`3tW4d*p6z*6cvRW|;l5aq?V!{YW2v-wE02?kQa_?jq0gz-1g@0bKu|v=~ zvgNW-CfwK|%J*%WFXG+GNml%-zatrwO_qZGnpIGiHMs0Rcx@BSP-@uo89pA#D<3hF p1I#39Op8e4s4-Q(8grS&7FzR}3|8Ks5wrTh1g$Serial Port: the selected entry is what you have -to use as serialPort variable. - -Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ - -This program is free software: you can redistribute it and/or modify -it under the terms of the version 3 GNU General Public License as -published by the Free Software Foundation. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program. If not, see . - -*/ - -import processing.serial.*; - -Serial myPort; // Create object from Serial class - - -float [] q = new float [4]; -float [] Euler = new float [3]; // psi, theta, phi - -int lf = 10; // 10 is '\n' in ASCII -byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) - -PFont font; -final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; - -int burst = 32, count = 0; - -void myDelay(int time) { - try { - Thread.sleep(time); - } catch (InterruptedException e) { } -} - -void setup() -{ - size(VIEW_SIZE_X, VIEW_SIZE_Y, P3D); - myPort = new Serial(this, "/dev/ttyUSB9", 115200); - - // The font must be located in the sketch's "data" directory to load successfully - font = loadFont("CourierNew36.vlw"); - - println("Waiting IMU.."); - - myPort.clear(); - - while (myPort.available() == 0) { - myPort.write("v"); - myDelay(1000); - } - println(myPort.readStringUntil('\n')); - myPort.write("q" + char(burst)); - myPort.bufferUntil('\n'); -} - - -float decodeFloat(String inString) { - byte [] inData = new byte[4]; - - if(inString.length() == 8) { - inData[0] = (byte) unhex(inString.substring(0, 2)); - inData[1] = (byte) unhex(inString.substring(2, 4)); - inData[2] = (byte) unhex(inString.substring(4, 6)); - inData[3] = (byte) unhex(inString.substring(6, 8)); - } - - int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); - return Float.intBitsToFloat(intbits); -} - - -void serialEvent(Serial p) { - if(p.available() >= 18) { - String inputString = p.readStringUntil('\n'); - //print(inputString); - if (inputString != null && inputString.length() > 0) { - String [] inputStringArr = split(inputString, ","); - if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements - q[0] = decodeFloat(inputStringArr[0]); - q[1] = decodeFloat(inputStringArr[1]); - q[2] = decodeFloat(inputStringArr[2]); - q[3] = decodeFloat(inputStringArr[3]); - } - } - count = count + 1; - if(burst == count) { // ask more data when burst completed - p.write("q" + char(burst)); - count = 0; - } - } -} - - - -void buildBoxShape() { - //box(60, 10, 40); - noStroke(); - beginShape(QUADS); - - //Z+ (to the drawing area) - fill(#00ff00); - vertex(-30, -5, 20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - //Z- - fill(#0000ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, 5, -20); - vertex(-30, 5, -20); - - //X- - fill(#ff0000); - vertex(-30, -5, -20); - vertex(-30, -5, 20); - vertex(-30, 5, 20); - vertex(-30, 5, -20); - - //X+ - fill(#ffff00); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(30, 5, -20); - - //Y- - fill(#ff00ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(-30, -5, 20); - - //Y+ - fill(#00ffff); - vertex(-30, 5, -20); - vertex(30, 5, -20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - endShape(); -} - - -void drawcompass(float heading, int circlex, int circley, int circlediameter) { - noStroke(); - ellipse(circlex, circley, circlediameter, circlediameter); - fill(#ff0000); - ellipse(circlex, circley, circlediameter/20, circlediameter/20); - stroke(#ff0000); - strokeWeight(4); - line(circlex, circley, circlex - circlediameter/2 * sin(-heading), circley - circlediameter/2 * cos(-heading)); - noStroke(); - fill(#ffffff); - textAlign(CENTER, BOTTOM); - text("N", circlex, circley - circlediameter/2 - 10); - textAlign(CENTER, TOP); - text("S", circlex, circley + circlediameter/2 + 10); - textAlign(RIGHT, CENTER); - text("W", circlex - circlediameter/2 - 10, circley); - textAlign(LEFT, CENTER); - text("E", circlex + circlediameter/2 + 10, circley); -} - - -void drawAngle(float angle, int circlex, int circley, int circlediameter, String title) { - angle = angle + PI/2; - - noStroke(); - ellipse(circlex, circley, circlediameter, circlediameter); - fill(#ff0000); - strokeWeight(4); - stroke(#ff0000); - line(circlex - circlediameter/2 * sin(angle), circley - circlediameter/2 * cos(angle), circlex + circlediameter/2 * sin(angle), circley + circlediameter/2 * cos(angle)); - noStroke(); - fill(#ffffff); - textAlign(CENTER, BOTTOM); - text(title, circlex, circley - circlediameter/2 - 30); -} - -void draw() { - - quaternionToYawPitchRoll(q, Euler); - - background(#000000); - fill(#ffffff); - - textFont(font, 20); - //float temp_decoded = 35.0 + ((float) (temp + 13200)) / 280; - //text("temp:\n" + temp_decoded + " C", 350, 250); - textAlign(LEFT, TOP); - text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 10); - text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 10); - - drawcompass(Euler[0], VIEW_SIZE_X/2 - 250, VIEW_SIZE_Y/2, 200); - drawAngle(Euler[1], VIEW_SIZE_X/2, VIEW_SIZE_Y/2, 200, "Pitch:"); - drawAngle(Euler[2], VIEW_SIZE_X/2 + 250, VIEW_SIZE_Y/2, 200, "Roll:"); -} - - -void quaternionToYawPitchRoll(float [] q, float [] ypr) { - float gx, gy, gz; // estimated gravity direction - - gx = 2 * (q[1]*q[3] - q[0]*q[2]); - gy = 2 * (q[0]*q[1] + q[2]*q[3]); - gz = q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]; - - ypr[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); - ypr[1] = atan2(gx, sqrt(gy*gy + gz*gz)); - ypr[2] = atan2(gy, sqrt(gx*gx + gz*gz)); -} - - diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt deleted file mode 100644 index 94a9ed024d..0000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw deleted file mode 100644 index 904771486a1a6d241fb5184282eb99780f730615..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 114920 zcmeFa4{%l6_aAiL{l%ElG%aF^6jR<0`9(}4QW23KrYS8_M8uR9DMiYU(niFXrV*tS zX@}7hD*SK3{~yKw@5le&iT_`>{z~f- z&vb;%`2XGb|6TYez83#~2mT3vAO1Jse=YtQNB^(kpTIim@bAZE7y4A(XVm! z@c-Rj9Q|76-w!|A!mzeQ+qo6EjreDnar|F{f5Jb2|8!i1!~{VD+~0@)-;00Er}h0I z;MhiO=iddtwzCm_wnghBO-M_^KZt*p!E#w=*HV+&^N&ewmtYr;RID=09rV{B|m>ca@3L zKKx@V#O*FqpO*QXh+|z!Px_Ufd*CPkDDN_kJWlw>@lRgnKl@Erp$Q)5(KymT;g7(x zT)t)-r!-?a?cX1T|L?&+c|mEdaeIMdTEigq1ZXI0h!*}o#_TiuT z*nf?KSKyz(FXMFF>DPSwZJeJ^l%zH7dJ+QyZm=V2Si@}x|U*8hx+E7$iH8&|HrKZ!Wb)pGfc*nF-&gcbf2 zJnVzcBl?vm{aT~{Y z$p=^A&%#5z-v=Fs6Tq`B%0=emKj#(UpTqxhvhF0}()o1W{yD^P4k<5jjFo1mtY7+$ zaV_9q`~F*qV;R~O=2Lln8h*+Kr8WK9hd&QL+pTn=U*QZq%jNqEh)d_wGXG+kd^(R> zZ9biwEJOSE&%@8Tpl$KndDiCBIOfwb{{tjFrPu{xv~A1Z5-=izv(Ki&s&`4 zW4xC6uh_Io7v@u1|Eo66_1%*%7i^r)Bj!{1EATMv$7z`tfoFN;%KWP~AM>XBa0xih zBkDnn-j!_N#N|%2fezuwaEb{>R{y)GaJitHO z&-xk1_UbzQZ@~WtERJ!Uzd8;N;U`UW9O&2j{!RGFf69Ywlg2%QpJ|nzbQS(Bc$VvX zAL3ZQ*2nhfIQ-l2vt6VU@%*RWLHKv@uXPdc*Y_A<>WaGdlMb5i--Vwv^y#Vf^#jj* zTJG=mcqyeLR^~G zTHgTT*iPjown^#v*Wv$z_~)9zw){blW`irl{U_^9pgZh~qrbeDrI+{{?=| zf1O9a&znbc!29(vo#y*r;ZOHZ`#!%y-2b*h+ydhK`smj(|96{Dd7gDEzx*F7#4WB6 z_kSXeb!eINYnlI-jZ>O2PWzsPpY`jw`(yimuMn48A@2V{9P7|B{rd7N#QndBV;gm? zqF-rNuyI-@(`X<5Kls^hon!QCzHo)O-(DfEh&Z-e%cNh+{9EvUkAKc(;x~AF#{EC# zyvF_hIPN>PcbPTdJC4;deEl8eA=h;Nvp#Qq_>Su==d-rcG>UXlI8OKo)z*@{xP4ng?!V-$_nS6O^D$2I zHNo$kKwb*>xPL`qc{F64Hjsxq~`i{WQ{;4eYdE!q2PugpoC+ENW)4(U%iLiz5j>5BC z|Nac(mdkg1g?xY3=2Jdp89GKMY(BP?G-KTw_vhdzuW3H^RpV$6VS3F+SL1#Qe%7J+ z{Q6D<&pI@pU*DexeiQzcKUtsB`iza!abVqA-(P^Ab!a~NHQ!%^pK?yemVV9G4nJj` z#?i0i{+HnA*l8U78rK0o>(Ds*HSRCN&pv4!{TlaI;3qxVFSeh43*TLYhvoP*(?0xF z;8{*Nnq2~(?bdwsYd-G7*>258zxMqy{L9t%*ATZ{eYX+k^91{0>&tMDKzUBtOg!tO z><47HM_4Xy0&z^I`8Yj_t4gb@)kVk&ho_fTvyl*okw(a{QBW1o&0e}knrp51NlgGsrAsM{x)N9yvh7*n~ppEwhx=h zW9c$Aj&0^R`SocW+r>C7lVxZe$DQrbxL=3g_F*%}kG!L0vJTDnhv5GW{Ie{!k!dY# z=DNvoQMpT3%ls|)ec9^wk20A&p=JJoSjXJ_7j2xjh3&R&`3>&-nNN9;e#@V~%`~h- z%cS4JZ!4{}Ocz((TgdfP-)Hp?Xta+CA%F98{QdBPzt0}?_u)PM_H^*~)G_`ZImF-n z4gB3u$=^(X%()<#h@y8vaA;xSpf@2YKe<@B4_d4!_T$r|{tS zVe|kV{N9Xi!GqsZ(Mfpl+Y+_FgWr7-xf8$D5r-eYnIhbPzpv>D2IMzrFK{_%D|DM+ z5G=6?!CWNC;mb&y%&(-Wjw0;X%&#E!MA1+Xm|sDF22apc`4z-*5HbkNuOQAwY`Xak zg7*2a2=ZpL=zk%cJ4-tF5C&~Rdd1DPv5+@Wv`2n-Ns(-M1hHp+1r)1ECAx0UqOL04h4bv6~s^!HGt|- zwAE(Gk}Cr9E2u)0hg*ndZGzxp*a2@xcuo;?FN9zb9}JIp7&P7sZSN)3=I>ehRQ9^Q zMN7w#P8eBnb3uSkg;yFfLG9UDU@`vhz|W?}FS3<$+6RQgqKD=;=lm zPv_rJfElPjH_&kzKEbR*3S^tmB$>V_y34{BuI{f4GWBhknprVi5@{fRAXrd8-LV~D z*TVJs&i+M&W*_d?+Ta4=g?<#GWaKUsys|+B3D*>JD9WF$sA$bcnr0vp zMrn-(ZIVJ%L0^UN6@4WLo8_#_aySalRaBfSxI%+#uG)hcpx%f1NK3V)9z3wlky%X(sTJ{UHpS@aZUeyE)i1HrHl( zdqAdoP`Sot0Nqo(0b<#-Hp!SsElm&iMifyb$FLO@`k39w5=Ak;oUmf6Bfx@FoIkrA z;kUt>5FLt6;kd#5j^apW3U|66w%1msMdHnt;R*rR$(a{^k zG(ud(5H7R@J11S3a{{YI=0x9QJ}ON1ZreH^6|S1a%Pd$oWRWrpQ*~6sWytXA=J)wl zHU)j647`MrFy$p5%`jR6N#Of49(Ds_(yhZRb+$(UOz~$&o!=+>) zW5VGC6<5O=uj$E-mywRt;>cz=^-+Fs9qtXdb;!y3vDS+C57vVkY+rB@2(;I=KiKp> zd*)2;{U+cj9mhBiUn5Z$+^y(FVIw>&mm{*4-6Y|OxDIy{+>9Hkgi9`@ zy4*UZ#(@&qh=NV*$^6)rts*(Mc8z6E3Uh%4qEY-u*$MtS z_)!0ZBWIxa1ahY4)PRHr&(xUW$l6iVZ)6dYdM&hQ8#I|3#dWf1b} zH5_y~%iz)M2vx<}k=#iJ1+IinIWh>dT-#VWD9j6eF5(in!h_s}xc3GfUcktBkXKm% z+!t(zEvlrqT^>EQuo+K-pc763oHPKp3ycL$pMr=viQr+B0}1pTPDL1n7(VJ#Lek!7 zRwU(IM12Gz;e|LdVUhDkL&Hcovh^*JzayzaDhVTv#F^skZ{s|fI)+znbrjq-C)Q08 z2>*j|;$U|wdRWv?mjDy)r3=6VX5Qw7q5D4ef|<#vNJ1!_gGQo$xRtX}NI9VZDRWKz zaH|)ioGLR!Uoq2FQ`F|7g=!7Jz3D4MBFttgz3AR3q6Ai`$BM0fx=*6$s2ARD=Z&H; zarUbpE<~v6AcDo9?DC>9@Xx$pfanH4oEJ8UF_-5P(Gs!!-gFpF-&5*dRW310q*Ypo zJdfnfaG&qWWOh7;2lM}Z6x}z)-{*b|%_W->s%9Z^K?@@^fVdDvz2jybkOU1;G!7}^ zR&R)0PD6>49|S%&oGuT7&+#ml{r6~((_Jad-=D^Qw*RE%nR>_!0~6Rz1i_9)4P*7$gLypz zmf{X#0_$iBf%NwBw(VBLUGF_7&2%N9m7z}7ED_6y9s)eKRX-1 z^0B&)$;khMBhjrxdSLY0n`r?kX{#s^)iQhhqHw+`{DvsK)^Zn(m4c0(3Q?mq`!XDbqR}H-wsEVCrsyGo$$CL}?_x1Ox46`E zP=;;Iz7Eoy3RD8xg4Udm_;3(et4}<5y@XyA=AYl%=a)(qG?odQL~6Kr5+#m3h|PT* zgoK-`iGy8Sh+J@UflGx8zKn8MFf|BM97oy)t7na>XM@*`=5Avfigsx=v2S!ekl-md zViFWl2%mwp08qSfjR25-0^#}_w@Og9jC(d-i?BhA1_4DGkNg%Fxk7meGprt>ICsvZ zu*FyhDLw(Q{nmI`n0#PI)T?C>^iH;8b~6x5NHTP4Lr{4NvT6*Rdva;4+0?rM3>|CL z#GOrZGPW-%j!e(1lBu^J`_t1)Mxe6HYOw5OFj;uLsS^95ZRa3L7uUV?T8_B=LCt*% zHw)vUqipKzpUM}*?3;TBSdfK=?tyHWAMG}BuHl*H;l>lvR)b=$rDQ2SICZ^`&cO8VZJs#MT3AyVXSm3vt<5)%H49$o3y0;scmkMZ()U*`2w{qxsE- zB?{eJf(;iiJI6C@+N{x%wr8X0EXHGrBSdJAqE}B~vo;}Ys6cl}j9C1FM!T(&&NNW- zv#?+nWZ6O(ZF?MGmSrzCLTDZyKvhjNNyl)P*>1bA-9c@;HIgsp-`=Q4q>KCU9+oMv z4a)dk&k)$-t&2!dU5J)2_zpVEuHA(pLY18wU$O4!Fc60Zygdmd(Ewz-DF#_r4B=-qMbrfZMAgZH@DpWrd@2&1&90hnT;)q<&FcqG=C!qtXMrlA{EMa|GY zmn{ELaq7c=s}k-E<~Zhag@$1RE`X3u`QS?T#MoRU$sMe7O(^tL3ufG!!!P08E5;qy zfLln{i6RVS4N=#1Jk1u13;peu5bG`v=Zo2=tvUjGb%pp~8oHAWH;`{effbNN3!UqO z%3~vFFy=4>;Jg`a8l|5G0a|j}cA^T2chCmogaT6E4bV-S0NZTv63-E=ren1IN_3Q4 zAHp6AxwROHtZk4Owb#%bl)F$HY`h{3gvDk(DvKe9thFy}c<#Kh0Ail>&4>BH^J{Lz zn+K_7Cu;HM(+-f~fyBs9<^pP&06Qc3pA?gc240r%`Rej63m31GF6vH z3dP);+uX_sY{j;|f&4T=`DV8I^(9+H<1~6MW3&9r6|CR}uN6My0YNF>y)WKxs zVFSvQ{r^e0SxQ;*dK(jiRHJmUyEOKxcHO8wiDrd=Giv9r_;8;o%fRumLag0rfN&vJu zjzAj1cJ?s|3mvJ7J~sH7wV%(AmC%dACmK%EYg;eHN(sF-J^(iC7N+*vzWoi*qOy8O zWfQA+x|oU!tnq~}Z5X%iHd*hM&w4~RkV%&=sCXudu4^b>&?k&c1t@(96|Jn>%o3u|XFx#;N)>O1b z1@z;M*+E`~a=$%VsA4Jg(R=K`@0tQp_H#W*$Kt&tYW9xDU}UT_NYX0Bg7O#}=-eQz z`1`3BT7NErT(kZn^H~3Q1nFb_7o+id`U@~oR&Y*XB&VqwRNu}P3WaC=ayDj~blzQG z;L0--GxHm3fOv_`H8ubjYl59GWF&3hjrnQc%Y0$>k(>5*7dvLkj(?>M_-T$&;)6CR z(4WF1$P=kZj>M92&{Z*)eMMQ~k$j?JK3Yhx97ukW)-z`;Go|6Y4Yuv|#b~6Y^pn6m zj7ZKH)=6^M=@ROUD9)!O)o>I#)eAz%CYPHom*Zltn%w) zERnKu-wjYaFS-b_dyqZAge=p8NwEo}kWo?A0wj|h81o}f5hzg3$4CSY<&9xJfecPT z{ZFT4mneLaDI3i(uZPUkotee*-aw6_Vh2xM9wjOWAb^N#A^ zV6Kg*lQWus@%SiZJU0ZmH$VETHKbQ9(>5+!Ea zY_#+|iX6AI_V%y?`M{nDz?zx}BY+xy1PYDQMrrEtC~8!{b-~)#Qz))>PN?A$0uH8w z`&g^?Yr2gSyvkSo9_@H}YyRU(Qmr1HPMqEdL{OaRaB(6(lQvz2HmT69=+l6kt^7~tT zh@xe_PUsAugBfsx3mDHM%CMNu;nIt%hGk^N70oEgZ#pMNA{ao<-rZvA7(*_@7{6B~(Bejqx2_-a?vj9vy|t3KeETT1D z$$=la3udf^wrIxOr|FA!Y+l$>sGrPYVZrj^GHVPss=BRkxP&duVNDZU(0F2G+=qMd z3WaC|SP-x>5Mpxm^m(>QMj^3Wke;k&$bujPNb;eLilSMF3?p}#dXLmYaBn#JlvOcB zi&NW(5z!3nR*5&5Xy%gEu%Y$QNUj*>-rPMTi-+xp47mDjCMjI~wihzsu^+K)fdL!% znQ+=LaoKn1!Ln1MVFZV!2emY~Ougm?B>jUpsX-r_LR_)aODm~?B=q?v2_oh@up^D1BVjfK zAA_1_D8@Z|0YXyfKH_(~@)ga4VjS-(-l1u8i*M`1Xs#$(Dz^j=eHeawEbF6#DeQ4L zw8_zto7u>rSS2}j1OhsNbn?6rtS77O|x7iI{QH^py6Dw!6S!N411d~go)4vpOf)VTy5!E_(0 zt0zS%^wI}gF_Z4!hn)q+A0Mx`BUwuVpLvg9G|oAkz|$0Hjf6=&507uLYpL|XnyDE> zzEt|4Iw_@Wv=kASW9@Zr?%08M_Bu_D+yXLQ-Yiln$#MpqL`sy>SH6s!7Of>9$Qn8{ zwf0l6@gp`!A}N?QDm2;D9ySLx6{A4#um|9uHEOemrl5oB+Y zSRSd<+MU8yV^KqIQrMt&3YeBOHrR|~T1w+YyI~>E16P8Ti$0}T=?zOz@=IZIR6?wj zq=g}j-r(0Gze)bmv;l#`eKUn{rjG_53wy@3knuehg$+^+X8Y6u#9|lkRfzG5$lX8< zSp!w=00Nj@m;pmoT5{D8)q;Ik88#{kI}yxJ+HP;eD6u*9V!>(lam~mKN+r%Fwuv|Knr<^3|_nF-i*DlhmoajfzYf*1dKs0FkyY3YNTxAVi z8nJ=8h>YfmIzb{}z|ar3Dp00@@pyR-4)*b0df#DFyB%aEgK6&=mus6xoeAW%!>gz$ zFIozMrjU(%?saj!$!kzBHGVLbOP2}}O)$+SQVC<#uNX38p@-p%0#W6t}Wi9s;VOyZ|2+QYexV^1MoV%4`9n4jG9R=#&8`rKilc(kZhKCpPIRa~D~gr7HW= zjB6p7UL{i|HaXaYm@=?;m!yM!UNU8#lunuZ=S!!|em-p%_k&YrT0eKM8&xii2lnEYFn61TahehT)t3QN$qcp(UOvVyVR6T96O ztj$(ge0$weaX+;S1J5i4x14%7Y$VGYml2QEwvHiLauW$!y}QEaK@@5*JURCU0$_1P z0OBX-7N43In6a#G;LKJW{_p9+vJsso!h=Tv9veF{s~BEsJeThZDqH)r#lm#|*=iK5 zk)Ps9Ymrf1&--yGwR39$8aC~dvb-Nn^_8P^0)XqarD(Z=qLlTm3U4z>4)yz4)NixN z9Etsi)pFgO{1$OCQMD)Lu$&7(jiMlGr|Ey}O(aaoUgDZDQ|v<6g!R;{@gQaKR%4La z&I^lHlvTb`Vqz+-VOBtehz&;cI#n3fue%drICElTxk3NBC??y_R_~$EQ_(+;Iji(ywl6&&j7Z@Q<@BZp7aW2rc|RvkT=%P*@!cV za@!%TO_mI_%(z%Sk!tV6L#EESog@nB)Fw`N*?(UM~yFF_X~%4C4q zBWG-4URvwzb~ZF395dKi?zq92SfoV>2`L!I5Y~wAI6}f$G`uSnsN@QG+SL9se&*dE z`rT8=x3QrX+#!3{0&H@}BszvlWk80_%?!*RJurjyH#&e+O>pN}@hD}n%X=f2!M!nE8Wy5ei35J2Cscj&`Y3)0p>*9u{b0-s{+=NenjmG`LTYD6Vl zkaY(QE_XM3t&kPEEtE$r2BQ!Y#JhGl05hvmq|tD!fvy#Hr!^wwkD@p|E+GO8s*2qS zdXH%O8+PxAz>TP|N2}PrWN)=RixxK<u7~r+ zJTFf@jpjCL!Elejj&e83Iz>^U&ZB9?{az}1!4FB61t)=A*`0}W+p^KfIGNNii{|ZyF{qn2Zw7$^Sd89+{D7*F zs3^UHze|m)&}f}N%7Ae@5ZQ^nq3tz74VX83`LGO)n+_mi7n>kWlk)N{#>%`h#U;dD zRTK~v>OBm-SP48%)kq-K8@oRXQc3OUPcg+4EwB^^&Q28gd`M(tM0tevuS0h0l1xzG zq^IyW#Lj#)%mGxyrg_V~R&53UF8ajHypF;qEu8Md)NMGdTW-i1e_VtseFmDt=(WE9 z*DppBcIL`4L+w;FuhW)|sv3@RZsHN~B((>;kr-*D_+*F&iA8WRWRt%#2hGuTnwv#E zoyP2D>C4BGxWL7LUE{VmBo{Yc`C)D=-Cm3lyOY;aL?9mYb6{N=^TX6#kNb%FV)P-N zMTHIkhDS0&?Z1Ut;BS6mIentyZa4 zTxP=CEE5UMf^#DVNG#|BG3-yQ$-ob#>|VRl;_0a_&9;yR(I?^(vDW0h5R9|gYdX9b zX@HdnOoY(aY%CPP*k|qZ@lvR z502-_DDxB4`&(Eik%zE7D~o^8e+;Rz^F4Vg7gMd1>5AFOo$?9-s; zNO#}hQXy3PI?&Mh99XN(4ZjUeFtQA6Q4YKZe;B{}-2^4l1*`|_ru7}XJA}7OiKAx}Z)W7Pu}=#j|63+E`HicRz-ZDksuK z#XC(EK}8cE4STNoBJl>^u9ZaCZYw70fz`pts!YqH$wDzZaAk{DmO1k1Lq5z;Jw97M zEbs0N4ota>@XR40HE|EXu%{55IJ*ftw4C9fleJkiT9=I$L>JkO5oJ4hOYIzm@=>iB zYX2PGWspyuF(5i&mNChflFzOaiQ&0oBIS3(*xVs30>vW^SBLpC#~onw@;Ho_c<}5h zih)I^dH{|GAy&{#7aHQ=tyz_8TKjONzL=kSayhZssMXn3B_5MIi8EwR;t)d8kHl4< zeU6t!jP>q|^B!|DiR>=rL5TT4+$kX5pQ;Yl2$M@Xj#a-Is|>aQfr|NWwjsb$S%F zc+&Woean^C5Ku#x>`XAqdUMYx_tRX z`r%514i`Tr=~ef3p#k%@dSf9- z-$Ez|YGPgRjU27Q+=o&CK*oAFs+aUy+$~>s9x&;kfX5u%Y;YLMcx>^24a+Ns0~0qR z%7D!aE`F`3V8G<1P0(5njeU~|t^k>8bBZp?KW7(_RDeo~Exfu7w8CYHlNB+})eDLn zgG!9y0zB;n#f!!&jZ9Rg0i##kY69)v+q_TPtRRDh#lsebmye6`nSXQHZlVnbXtZ%n zt|ZQIK@x`$l71F$UDsGxn2ujCjq*+?8@;ysHQNc}yfa!41G%eI7EjEmVI8Qx4W>1_ zbz=pbwhzpa7r%#d?f=!_4Dn^&S*7WoPC#ub8m13inYm{M!p=j#*~qbSPzmuvt_lU4 zjx8YApsC*l1slhH9YO7ZwAB@)lVxh^xO&vE)tBf7N;w}>B9tUQ+HBcp^B`0Z_u5JuJqi$a#<#AoO zr<)R62bKU8+QdjYELd+yB?rj2eG(GC+tXcu3#z)&i%Hd2wapDwO&_Vni|Gh$Fb^!Y z!V}ZpXtPLQIhV;|BE+=6mPHyukK5ldDZrrJXeghXNb`#%zmQ;Z{wG5z8DNbR%}=x8 z?4336Ar(bCW1TC71a&v?_~xv=7s>cYo=KtSHTO&@Ivb6H zu?u|v-x|I>fCp17S|5|axh<_Nj;6++FGUIIk&!V1*8h{DV%q7%SH9FHp!&pdYfL|L z^SUtosKquo*bB*I;KKpIb!eC_t@6j=&Ys_r2{xanv^yEV_#O>fg>xQ7qCq`r3kspHk8=b2bECYAeZ7Ka_4tSZ@CB__VlSc7z(!|$e^+w>`bGlFsl-( zpNh`hjb=@EKrnA<$7sq0)%$QAaJu19CAMB*PUa<0m8be=ip817Cq)f4WDGW48_9?B z_Ql60!#Ne9lg-GL;wW=d#PDV`PCLknaby!}GW%=T#sF2%VJl?2ftuCR>Z&P2W8lt7 zD*l`^#{|GRng)1H2Kf&-m(05*z1tx{vl)|a$l(U!8TP=^l3m?q(qTzERuxnorLCfy zdEk0rc27WXu@RV!4W7ZK>$udo(0|6L@u~LN1|XC5#m=^+%=y6XVx{-RPo-U5b(igb=_6deGqpOdZ?cJg`Wi z5&c(z9B~6_OUEwL2b1TR(jekwvE@{r>0iL6w*L$!rs8ZAoG*#{gi$qF(2k8=BVqpa zNz)=Ws=~Yk5?$Y5r{xaLJp&``0KA}euBSP}H-s-*RFv(KDY$!PRwN-(UDr9uBmkg{ zC;t6;QI1fk)=mNXVvvRTLh1mRviM?R7&AQs9_T#hH{PR@lK7biZ=n zwFQb95KL9g6NPJXV}0TN$%A$`9@~KmZ_V3=Yp3Hzjc!GKYcG$W3ImDkNOc!hIvUeNpEm66^RBySQxRW*^OSDWa42i-ZUGXM`4Ze$z-a6{TI5Jz zJs1bGa>1heJ|{bxm$1q3rO8bfV171F1MD{4v%fDS?=eU`3)7eEP}g-2=8A<6k2`lF ziJQ=#-()a#tKTrU!Fhf}8ytSsuP!6hukO!{L-(yPX?m?~02lYy;RUki$AGcz-dA zq6_tm0p+VYa@OvXNkdpu?S(?#f8|6s0Jb8-Q;>7vse8 z2|xA+?Mv*QGjn`V9a=i;^gzkg#lt!LT=L5>U0UOHMPtz=tj$h9D!N{%6n91OP}aPz z7=AU>R_;~tY;#CCNwr%w#U6e;NDeQ89xBvmbyx-Gx!GlGGw;-X7s=!Sy*UbR<$~sV zdrfnrT(dfZIzWFo8(9jD;roKMB2y0G4Dy}eVBF4Uum|-_fyzs*6jM(dUd8#oO7yZEYSE0pPtbDt>CFRB@vG=tXJ31~l+Ed?#Qn(Zvd% zg9SMb^V=aaZm~j|?Tb<2QW(u`mYn+2#DYt{(Q_V1Di}T>KT;-{1Ye2EUVM!%(79j*0)lJi;+HKT&zP#7X!~7ThFri=78s8&72_>z z!081xNJh-Zd69}yfFJKOW3vY1MG?^oA!6pP^jB&+o6Qd#l~S=$X&)_2x;+e#>)$d% z^wO{x5L~VVUNTGF_|h3_hHuv0!Y^hmU(1=#LU=*4arSprL#K*feARXe$@cg8RfG6FF#}nQ0O|kSn1cyCez7$Sxb88-3RK|E-Eoa|aWgP&8T zDth^z=9{)=Slpsw&bt(bMf*d{RJdEVG`k-|=7xm%o~QIt&;sArEv;Y0=7dIuL^ zHk>AhWCMQPCWcpd1l_eiD&DO|&NUY&m|*Eir?3LcV%U^ve$!#JQl^Eb8HIgB{dBiH zd}xSekZUfyff4VqQQ-wuKgA*ePJXYAH{HU)NCtImYEP!(6qF+!J+zdXeXwmhcTNft zCbT~1V7NEAfboECnn7buM)Q5*bo zP?PfnctXptE(T7tcm_N2&|5b{aVfeUE#d>$GujAsm%OH0+_jWBAe`t3F6A$|%DThL z$kcYAFB@k2_IH5D*R?cp?xp?_nph{DL>gO@ zkO8qqYGV2?N#2JNeP8l6BlSa+`~WUwMi(4~E~AxeFuI1p?QFuAw3i+?pT{C}DZCQ* zsBm628@9~(U1lJi-)g0@n0o#iOpn{P#9L6wYQ*1+Y$wGB1<<`b0`!tM18mEimySpR zJjoPI*UGz~-mBFbJ6kmSH6Q&d2>;p&+ELhh{9}wgKq`RGn@poHswq*A1G_h~Q9x^= z*i9oxU1od!$E2TGrX#tshE(rW6gNjnu3Kh&M|e3E0@4OrL0cFrcU@uE%88*un5r5c z=%Kxm(7e=2TYag(VIh-G1rz zBmdg&3(YsD@ry4eqagft33GIXS53LKZT)iv9I>@|+Dpw1CnCceYKq@E6NUGWAXIzw zNimw;CE0gpqXD;*uOEoy>r{AyN3SW|{N9churNQ6*XVEQnGUm$cD{Z^{rnNW2gm*6 zF&$^{&H7wae}$Wq-B8pUf{GJZ>`=_DsC$6I;@0 z0}oe8W?B*Oolr;{dbb)S?I5o&zKy>DhUELAp(}j;^$?EXAcWSOoZyD~W^}b)+ItQo zEC9`k?X`W|+A|Rr7yDa~^eM0OuP>p)BGraHd5>mWEY0vb5YYEQ3#d_h1oU-#x3xFR zj0H;JxP>_GJE!Be`!0_Evd?!T&RK7;^aL%f`*5N8vU&3oBf(~}A35|G1x%4h6;Et` z;J*>goq|f%M0`G~WBSeX&qgOQneErG@ax<73Wp(Vjs?vFg~HQD5Ie6L__|ld{IKq& zaiM}3gM_-liF`CgT}@qnw`qY}PIYSsQ65^aZm@&PIA)o;!AbJWSxgY?;_5qn9kGkz zcFqEY@lY42TFmZ3bL;|@!K%!6$?+`>`c63%HoFmVt*~{{1?-&T`-?Ds^TvgD{hL8z zg7w3L-JYyOr3M^dD}t^blleFhH4TVPqhv|`d5|R^YiG4x;gv+Ae?-8v_Gc9`gPfhk z{0m46PsqH~ImTB4me|{lT`sFXS2j3nm z%jk#-I~SRv1Qua?J3N@r4{|iFndmDJw_$rl1ul3T8Zef;bJ1WS5`CkB--%RT9E%+1 zDk^Xt;;@#|jRFrtBw3pXLctYJ9by>Egc@fA#m@jSm#iX1wo1}esiW1fh=uJU&KP)F(HbV`^ z^OjTQJJio+L>n=i3{#)_OPkDGX}jP)fzr6M6I!T; zlYsu*Lx0roT!#yDV^6MPr8UYw97hB7d>&2>pITagw|l8sG{$xC3vVf?I{kQ7xdno% zV~LHlFvRW6!ubtst~43ut0^cyE)06?M|my`>CEC?8093ws3;L0N#)18eiG$V94ubg z=*q*xU8a4uJt(aD+*4sAQ!-2U>Nml-J-_-ewk(99m;432hm5ZO{3+c*epXaIXX<^I zR6jL3Y}7E@PuQQRX+dI-Tz+<{a%&XQ`oE${zX$`$gX z509Jeyp&|$44|btcPeEs)`-pH=G_4rcCLGwfWxTg5;#o#374-M_-Vi_sP3f4Rie~s zb{OL^3oE953XkCGw-Zx_RJV8js=l3=95|zbC2V+^3p8e#wT~XD)iFkz3*(7zsz_uF&RA~Uh@$({S7K=Pn{B_V!uFel@Eo8 zzcfB%r|aH?Z{=Vq#YV$tg0pW^I0kWWnbA8Xe)OyJ!G+g8!umH1goCg({WP%3w?fxn z8sB!x-H1@n*WnuWQUj=Nv(+GCE)*S!(awy5tNLLj@RDC$1dj7v4;oe%_$PdcnugVd z{>owm-xhWRxBze3!zTzH(~cRzj=O{}qT`@N;F(+!0G?oRaB7MyhUp10{8@&q{kF{z0SlYM!u(fsjC~NojQO*V)BTLPNQzeGNGA6=u#=%RaX2H)h z2+CsQf7e_ma?Ho2Psp=th}Rxk??+4(g{(&8p*jXxHXY^QB={4_+O7dSq* z=V*Q{WlKo4%`WJ`E)QxfjZ?TPZY%4XhO_dnfKHs#q${TKsenq@dV#eYd z4}1ewiRr4;XjN*i`Vxk!Ro?iO@1vcQTqx`EJ<&@q45r4@w2X`t{hl(ZY z!ljh1@F|LdFo0XLk|Er#buskxn8v~9wbIuUi2kNyll@PImZ1i^oLt@$YkP8GPp#@x z$tC?0*Yjj6lc8nW{7sLM;l1U$knDdlvsGpCSsHQPln1+BehVbR>@CaB9j#-LuHyl(yk5)DBzZfvWHsbkFi317M1Py{%k2 zl$W?gu?OX$UUz4LnY&Rh+L!f?UTPQlj+#V2@ZA=tr*-@r}ab~n|uy2|#gFmcc=O&dnK_@gh!6el=L8Wv$!A&I(3NEE?3hvW&PRU;8XO*vfqI{ivRYtQar&oP( zt!kAwzIxtB?S`bisV$MTAM3D!VSh4D5}2bK)N{&K%~2nYO&m!Wqz-<6|&XqsC9G0SIjX-Y->YlEy9%8?-61b<;p^55$j@f; zS)|vpk&X54-TCOf+<4+wZS#VDK)V?m-$&eqqhVP*!$d$$H&9R5FdP*R7*ri- zy`8U(L`C*tAMPJsm>06JoL;RF05>YmFYuAi~}PVN}iKH`ru7J?@h2Huq&?yZvV9d=~7t zL+?k?Fy1z{wjG+Cp(B!*M>!9P*&l@=hb_`-jxlBzc1sdx(qtOWqRQ?Vb5SmI+wUex z8gs+D+l;MX+85#AnR zBu$l`jg>nZD|<3_sm#IHmpB)zInv!XxKs%9(|yP6bcKYteX8_m>Prdq)uEM9gnamzp)K7il$;Qi9uSo|A1ZS^^yN;6R)_YZ zhqm;Prpy`5mph_a9ifjNp)&iaGDjs}?4)FMgg$zN$~^{L<_TaZTj_^?%RKk{r5^cR z9mkIy$HtC6eDnAH)pbGjg?D(N=TT@x0PMmHEOyKo&r8_{7=>LU#eGAq>w5lW=bp@3 zYFSW~*VW)~-hRAFisJ_$%xyiq@hkLnMxcizMQ|Tq>VU8D^7Cx5fHRi}dKRI9?`&_x zQAa7{_xh@+7Y`+LzPlN(LAJ`9Mj^S~j{;+lJ6H$O8=E#NGanKoRz9<{c%~w=rx$xj ze1W7fsA=hWTUczbc*k%F6ocAV2AO|~H*;zHLI;X!#u>|e&*tih$3fGpLSeM84PUMx zWR5)gkPq`ykI&W*FUfB0z?9~sJBKvqeT1mar+}F_y9qD*YI!M$29I39!tL5D65y29ISQc6v0AKrdn%uhYJ>MPv7ksi%GqhO|y+k2Ea+hbOJw_A{Bg_)JmCxAPRK<@e;yk>mQ^&CcU zS5Sws7_GBqY(Np?nHw0mby{k$76dqrX|va1P&YmYQz{>_rKkepg8JpDFzt z*uSBnt3zuHH6Jmw-^BiHb!cU(e$1@>nRf@PBlM9Yl(KhDB^S%IowLNonYM3!nr+kC zYhk$)(DlFu?J0%EY7!g!bp*8srs>JhGLJbWm$HNzGHHTLnIADkSV$QQISR}}?^gX*a}U>0W_$)K_x z>^GyQ)h1IltQN(syel3}cWl8u<96_yJg0Xbt^;#r;fy;ilGsWV}GY_2V!z0H;K7u< zUZCOy9@9eM@yi8ZWbeS4%NehCa&_-85VIYdf+~DN56}`+&Z)E3fV6V^7Hyxr=y83kng{jw9ylFi?m>Xg1Jw4usJQMo>k9I@207;ZvrfI<-QL z>ct^I2R;%drQ@4NQ72EsVEPxU|8BHou9`u-~8*VsTX%i;3Jy zb6NRZ{)v`SgN6{X#Hu0KQqzW@r%LP_g8o8A4k^q2^vH0#=PL|%MCMIo!UvMhB+^%r zxkbwG1%qqmn!zym)*5T}1{^vGlUUcogZA0oAkS)9Ori2)dq44!cu)^8psG z!-B6X`0qsD2CY&ISh%ZY;!WlU#<&J!=$I`{GiRa6;V#EA2Sr4Qx=!DKX_ zytrh?kK<*`tfpXw6BZil-H0-G+NpVK{Y91ym~b zbAxt@CL|Nf)cJ{xKmx3gUH#0d5{NGE>M<6oanb z6*t`TQIA9|H-DF(!KzG`{Z#StA1fB=|00U6DzC>bzHdBHF&{0IY6{S0P6l1>ojG2X z995R}MPGk1v63YSARl+e$?4NCWI>O5kc>f=Q-T?e!u5WXW|7zQT=ruU6LrSZhcH!r za5Fnt?i0p%-;(r2ONZ6Yt_b+@DemMd9^WyKwa?nTRTXXQP!!hCYn2SumQ;U&@}x)c z*b5O{8|7m{60$mz3g{Az&}1Bm?vxIbL>0wGX;LMB7owe;#s`u(6Y65k_IZI+{N=fP z-`b$eoDRx7!Wyjf3@aWEeIJv~RkNwgQ>>tiKE@i9JjWW8KFC_;N!D_YvX*<673ycn z!>qw*>C>!bA7?H5(BldZw3<$r8@qC&R&Kn?j+7ZAN6~US$PyD@>CUmtu5qe#$N0r| zi>qG{!+_oS)qO!MUo8287#dV^kD}xvMd?k7GFK_e+@<(Zmnl{s?18La>A@a6i;;Y= z=jkmK4cDGo-$K+Q$5Bri zarlq*tO^BC?5hz9-xA}jKJE8WLZQsi;sRBPP|#~u38@g26$?Q*x$wmV1662aSHw$H zPMB+nKzSffgQjn{Mo(o=fMgaag4Z*0Pk1&IG$@W4 z_NQ@mxKohEAsZgXN#-@dAI9OXWj>v^QS8OZyj^%(ODbJ`Rz7;*r`v^Yyz={7eF*!V zXueKg-id&LnMNs1gLEGyZxM$}FRmg{63mV#2ztXiUW6%y7GLzmf!XNH)OmsDru_EKF@~vvEF?K`$1ZF%xzbAo^H#!WLl)Z273y@_ou3Z zHOI&+HZ7k5?l)HP%p-?I{!!hA@ts@4trU#2f$T&rm>&*15A=<*h2L*RRk4Hcf=xTuxsBUK?1NR#X*a1SY4D! zzU9j6Y%$Efx`QJW0Jo+b*?1z_a{`HVKMQS=TX(REe{9M`P(1!zOiT*s8_^*q(Ug)L zrA=`zCy-TBW@ny224{^)B#GRJ3F&$%oiYE01Tta?Heh$-S}%~&8uMc&WwJ?u znUyJImrTnflCM~9PW5PqotSaTszZDyGiGMlsmXLc$lUaVV7T58EV5@5~eHNrd^P?zytpr|Ek)%vbOG#I5R$@~5An8s4lb(}hrzA3$&d9P8vg~{; zI~~i;#Q|SU)UU3?nW+M_gEDjmElcR^ z=*yxAKcUfQ^#OKKtd@H>0S?>4)Vm4F3`Q9PTp9aY7x^G%C{0=4N;T_Jy}Ha^yPQs4 zMx*}RjdrQvaGb54Qf4OqB9;!pdOs4g`ek%nmHT!qF{`h|0Du43cPHpFVde)Xh=2|1 z;$VZ~ApWZgY7b1qlOY`17_|L$I`KDPERK8P>HMxYIs|e5T;CXlbecllZxm$}A;0z3 z|4FErs>r@9#8h=jl#Ho!hQ#Sq@?{GI%>6i;6Y9`xG-qrBCNogj!A3JmP-8Q|mB&bIJ8&&c4?!z?LVt|ngEf0or~`TP zBygPSOf*t0WyGlQ0eO-pS(c>v=}=$IgwpY#t?jn-7la|1#mJ`P;9J)W;hb4bg0VeK zg4U3x!(%LHsiFA>f=V0o36KnxFt%r3aZ80;$&uYMl)u+YEEWk)*2I3kAHvnY$|vr& zAnzsE^KzPxE^vTn-Xr%0H(?(CvPm0gitP69@K$ttMnIFQaU2#xq_cU%nZey=Tz`&n zVDm!MlS%Xq@fRkll2c3bsLRsSudd?KO#j9&f(tUUdWE5>NfjSs`2(}bN6}sYJHk#V( zXoGhI=J%CrhRrKZoOi{b(gw)^$xtb``xTVxafnT<$u@OzX|~AJ3T?4d$%WctfAo57 z)Bk`&gYJMD;FUR6KX~5Z_zUzA64qikq81IQ8*IkYsI-4e8g=E1b_k@ge2$_F);w*C z5-i85@VsKuN*>LIR5)kCubru}0F6I*E^R60$P#ue<;60LI91ApUxWpvudA=xiN%bJ znjLF1xMpm9e;MlsvXxrLSXLPe8PVmeWW<-Tlo9>8)-smi!K%1P3zq7481rvf+>~L- zGW=MM8Ow5FIX3(fJh&=u?CPRgjZDfP5I0QIIEC8-+ot?SdbZ6+Gr_h6^CeC*xe;2} zv2!t6a5uh#?F-TTwq1+(F-iD48_hTJ$3q1#rf|0TVyfhfHO}>MKE6;Toay6b6btd& zEynj)RJ-lDIA;af0smqbKH=NYwFobfyW#35d}{{~z^>svP*B|s@YA@p zsq|hf(l=}(ad1DT7ki3kAJ>e``P3`UE9D_Zqd2&Q*JAEl;T74_e54@FU?>$_S)#0Wq!@G0DM~R>K zOC?xIe*@^n>j$dbl4v~m4ny=(>{0MYv4ZDEr-#i>C4q-d9olW9!}Fx9<03Z}1Kch0Adhh@hmX*X zxEwD-pSf^k9z`-13#t1c(lEmgw)3%|%nuqhe=yi%`t@)_X6wFVnV86;K(x=XzSq&-R~-&CU)FPmV-zTiiHCH@m=?0@t>H==#DYheaHiX3!+@ zv0PkBv0yxFA@tJjn6h6L*Etkqww)b7f+@Q`!W+XYi;N`%=5D;=#R(&Qha;K+EE~hm zSIE`bRLjnzvD*#Kr9}`uo3?K{(h`^m3-|+@*p|ysEvys!4cfy75IK{uZR%L4Sn5F< z&+281tDYv>nj73JCd8DX>qxosZMUt*_+Vq%E9zbbBiM~Is;JXwYz%W-2_RxHPd zUxo=+#f?>WoumFJKH|jRR-!5w(gvUDWtb6XC(5U@^)aaXN6e zJqXU_yMoHretb=Dy8mpo)-P^q^pk_18vFFnPo+lwvj)DZwSTElnC(B+l0%Dwy{-eI zE$-oCA`XJ!4fM?xP`q;AwFT;!7-UrmPZX{N!4j1J`zH@>(7p;^Ab;WQJ=u)bijrjt z93>;Hy*#2!7R|4hY?Vz%&pjAq#rMwS2cf?SRAJYb1>MivFh@25*_o5Vm-$OfMw;(o7HiJ<0SXDk79lYY?zwit!XR z)C4a-J5{+=J{51Hq2vSlZ3s@??GJ^e+iqh05?L9uG-hRxBu(TrjT0nJQ#eiF6n#r{ zk`j%iR39m$jg;ylpRI|k&S5htzVsaS7OwQ*r^miz=u1bwWZ*w*+<%F)-7Q>hQTqgs zunO|2>v=y8rB7370UAarijo4&&o_dKchYJuVrLYzKe1--tOy$Q!|tKEX#Qw285NcJ zB#K7V#Em|@B7L$D`3IDe;c(*BqeL}lpCpS4PKNd>Y>Xe(tFVIV2;1T)@!?c6g@J9T z1e3PSs%Xh1A~Y3yzNE@T7n65*BWJ7pt=A z0?!9Ibi3Jp2QS#RV|f>zzGQUUy6(YTvGCz>=T0X0(a@VbctyVC!}2WXMj@LnZ~M~} zregF+3ez*1LIe|yNlbb%Kx}$F0IFn30IqaZ0J3CZ0PeHa2IMC=Qh$O+3s4tDs8`(| zhf=AisWpsJ6eR_kpKk;ePvg&#lIEQcN!eqVI4OP1`yNvAN3NwO$yM==Vl{~~7u1uu z4-M{201*Jw3FCLaG9YDTQM!(0hc4BYpD$ghbSfvG%1WrRG75XGvQnzPq;4A!<@;+kOuYoZ5&JgaBNAZ77ZW02W?3q{+5 zxXM=`jfEjy6D!p66ZKY^LioGw?nD?)-nCXdi~q`b$h6Y%kn)YenLew&VsM6s#E)o$ z!>{_)WrX_G{kd__M6B(!38$*2t+1f|1fP;Axda7H_)72AsjT2&s2{`;umdFiSXSux zQ&B|}6B)39ZxQ!R$PG~W+hHt~A7l;n3nN*EQNJfY>^?}C$!8+~|r`eih=&eiK4QtT261#v&yaj9LT23&{8tXL*$33xdm*R zk*KJ9tS)>oK(gbw?Xr0A!*_;t!0p6ai{d*{4bb!U@_oZ$gC>NF!=%L~m=AE6=D}Mm z-MFpeVc@Mt0a2koiIjIFC(q2704Y=HelDb?I2zz~8`2yg1mb2{u?(y=8@Q;{fm`|- zS?b8G^zztL>d@_TuZ)?NyWd2Ah%JxM?sUktYe^=kL-=koJPxrl9}QFQQUpFGXfAZw z-RIi((V{=TTdYmfmza~QogOl`vTi_wJDF62IH?Nl_s z(L_n3s)nPSvv;tSPg0k|Zg?tb2`!M}$AGP`a_L8v^kYVyHN8a${vYL2Mr&h zaqsNxcrJRRns*RX+>VMy07>rkZ=$)~S`JQl=cCuPaS+$v==;OSD_@P*ih1^%*e#Z%s2dK4>oobtyQ#*O@KmrfoJg2<0c6pGZ>Z;H=I* zpES$)OI{$B9{ZA^FCF=kf&YwgU#^`i;B~-%hs;LXor?4C!oqByTaas^mlKw3e8z?g z`q`axh&!OPpo^Pmt$vty>U`BJF|Q$O>Y$4g5G++MvuPsOh(h#iQN|6Y|X7`@u}0bu08d|vp+i%Gc!3W6Ejk0 zqyKF$|D#@b`XT=CT;elc@%OuAd6qR-7Gm+ql4~Mp$p=ehLb25w<9yo!bhV?nwW)6^ zHSfbTufXgg?S=yLqRW<{!el2ltF_~U52A^>eUsz+Yu`ophR1Qwuk!M2aqtkS7Ta)Q zn_&D*r1vnS_Y`FM@yDt&{c|B6hCLq7gENka=j?2$zT8+wf}RTM2z#K2mjSEB5d^B!&F!Kyw@T0L`Khn7G4W>zi<& zpg%*Wp#ImM;)Pc38S&U6((8t^a0!Ulc>JvHPR`(Rcc5qwKUbmQZA@dqQL==)@>p`z zx!`h3xVX>}=M@ZoLLMn3pnw(wA#LQ3^?x%c=@73p11>C~+2IY-ZL_zret9UTa79vC ze|wrb-T5~*_WkNjsJ{SaBkdJKF38%0r2nOJG zL3E;-y&&tLe_#FX#?&!U}9gMwSchFbXlBd7=TD zR-@c$lzR+8o(-d1G$P1kqhbSGSk5>rFjwYl=zfsL;e+5U`wCDxs4Miq4PQ>Jg0;?OGwh#BI8w{Fh91J{z zK@atj4(dWoMFr49U5F{th2o0tdN`!Jx@QqSf@pPL+2;$bi(wMFsf*#dfz%u}ar>h= zp`*G5`!zgupOZ#_=a#;4J6CEi_(R$YcY|%Oy4p^4G3>8cfpytVnz__HX+NT+?o-Q8 z>K5?vLV~(aq%erh#I37~VZySSPhQhP3#APE^CN@pPAkI%n{P`__b@Tl&F4#;IMm91 zWJM%59e6h)sWKO9rpMKJn(mi+!}R-6l46Yx{=G>qzLt( za*$1YQ|X~-!=Bx`b=Lbb3S%evZjrswR3c?4W16%&iQsU32a zklEWkJjFHPMmBd#b^?tZ&$zJ8ldu9CPxNsyFAjD!Wdu>x(lfyxOx(faRTkEh@bi5q zP*e;Ruby^ni-XQrbv>KA$p*028>S_h0Tv0OWTbsV6-*7HG&Ihm1413!6Y1(fbaje- zJ`hbZr6Y>-04XV(k-&LOnT?Gzrp$&$OL1E}zBA+19 zrNSwuXjdQgkU6$~FJ_6na%Ve66|c<<0vyqVra(D6^*qwrcB3aYx$ zac>WNWD2!pMTual2BG%@Wt*Ct)DcJAexa2crG-{4Z|5k2#T)kQCfM)*!DwKsMxUV^ zm~7FYJmHt`ay$zBweS%(3?+~`{%9&6W}mlL2M2OShMjg>w8i72a^1KB`k4*y1YdwsGKr-jjeYRmjhT%uvLv=26FDD(E}awOxQV${4o@T z@g`#gd||JohtK6xPZ=EBLcS?qWHCDGM13`=dAe6+xmM=^rdtn3$c)<*$PV`?m(^A5YZ+^IbnV~V~lSBw8BeQbMrKTcP0jj;I;`@MA^7TOrGQuhU z<#Me5KQ4=-zoz4RmRPm{m2q-{c}v>|P089U>x%mtQ1@p1K&CTAru$ZT7Whj9uFB$-Te-v^>4UL5MsNiJ$1|L;^ zmI3g=Wa(jBh_^jp$2e?WJY`av;BkfMwllRjadJUbm)yAB2N(-n9)hd;lB-nhL47 z9s_0zif1py_sOf?trL+dN=uGS zv5;eZL*Sf5R*skXsm_5rF8Si<@3U@7j*Guui^CqTeZC?V=EOxZhIt@fwVqI2Ja&)C zgTtPz&1+pctJB+CK;6sdweu8@B1I*QANbWwLdW>tl=cUsIC@yJ(PeTJ(kSzBfc`3K z&{b;yj{g}qORn$*d;1GhM@+fYe3 zs#mTmfSae^`v}LrHCTh#>9G3@6%p7_vibMG`Np0>bm}z^@T+>?E)~VUkB6R#i@a7z z0J|}Y8R(JPZRSyzgfIN|mFl34;UUvnrLt!2qGjqt*3V;N8;W7K1NvlaaIC-pAmZsb zF8#3!;LEjFxGv+<$61^iVOrDgT47zqV)G|lcSlOcti87pAu3$cH8gE8khLfD#A*Fx zo+oo8ne_{ERtxzc0|iEP{&r{qCjMn@SFSWBD(&Y` z!&6K=!MtqC;5-%Kw(3VC=p4MBC~Q<0&Hmen(p3}ZroS8O4L<_lN@_`LZe3FK4&tQD z6fFZ0C~DTo77k1F&WchH5BJ!Z+A!9cWm;8A-MnupU|rb>!k31IkNl}n!cCg|?&(4& zJU!vB_gb9M=hW}+dEOJ)R^Gw~eErbHqF@<)EZ&cR%FfJcgO4MFFb#&a)aQ+ zC8K_s5`22mIOeL9F;_Xa=l6r+5!$@BnY4h!doNZD+Sqc0g*uWk3`>u8H4`Iy$+8;c2)=dA=n4{n_ z!`|M5fPMS}b`RgoD7Uk{d$FV$cG!7u&MWyw)sy^zugnlDXd|)B?c18r`8tX*d}h#6 z=TjSAE564SP_}Q~S+TumUxGvmy>|Nl_nmURyp?dyZdk8jk}T@8E#w+SoT+Mohj`S~ zM6cXFwW`3tW4d*p6z*6cvRW|;l5aq?V!{YW2v-wE02?kQa_?jq0gz-1g@0bKu|v=~ zvgNW-CfwK|%J*%WFXG+GNml%-zatrwO_qZGnpIGiHMs0Rcx@BSP-@uo89pA#D<3hF p1I#39Op8e4s4-Q(8grS&7FzR}3|8Ks5wrTh1g$ attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 - -This visualization code can be executed by Processing. - Download : http://www.processing.org/download/ - -The visualization code works with Processing version 1.5.1. From 7e95edbbe848ec49ee81dbd85dc8c91558a83aa8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 28 May 2013 19:02:16 +0400 Subject: [PATCH 45/89] New messages added to sdlog2 --- src/modules/sdlog2/sdlog2.c | 189 +++++++++++++++------------ src/modules/sdlog2/sdlog2_format.h | 2 +- src/modules/sdlog2/sdlog2_messages.h | 77 +++++++++-- 3 files changed, 172 insertions(+), 96 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 8d4d2f8ced..48d107945b 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -81,6 +81,7 @@ #include #include "sdlog2_ringbuffer.h" +#include "sdlog2_format.h" #include "sdlog2_messages.h" static bool thread_should_exit = false; /**< Deamon exit flag */ @@ -447,7 +448,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 25; + const ssize_t fdsc = 13; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -455,7 +456,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* warning! using union here to save memory, elements should be used separately! */ union { - struct sensor_combined_s raw; + struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; struct actuator_outputs_s act_outputs; @@ -478,9 +479,9 @@ int sdlog2_thread_main(int argc, char *argv[]) int sensor_sub; int att_sub; int att_sp_sub; - int act_0_sub; - int controls_0_sub; - int controls_effective_0_sub; + int act_outputs_sub; + int act_controls_sub; + int act_controls_effective_sub; int local_pos_sub; int global_pos_sub; int gps_pos_sub; @@ -496,9 +497,13 @@ int sdlog2_thread_main(int argc, char *argv[]) struct { LOG_PACKET_HEADER; union { - struct log_TS_s log_TS; + struct log_TIME_s log_TIME; struct log_ATT_s log_ATT; - struct log_RAW_s log_RAW; + struct log_ATSP_s log_ATSP; + struct log_IMU_s log_IMU; + struct log_SENS_s log_SENS; + struct log_LPOS_s log_LPOS; + struct log_LPSP_s log_LPSP; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -514,14 +519,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- GPS POSITION --- */ - /* subscribe to ORB for global position */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- SENSORS RAW VALUE --- */ - /* subscribe to ORB for sensors raw */ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); fds[fdsc_count].fd = subs.sensor_sub; /* do not rate limit, instead use skip counter (aliasing on rate limit) */ @@ -529,89 +532,65 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- ATTITUDE VALUE --- */ - /* subscribe to ORB for attitude */ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); fds[fdsc_count].fd = subs.att_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ATTITUDE SETPOINT VALUE --- */ - /* subscribe to ORB for attitude setpoint */ - /* struct already allocated */ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); fds[fdsc_count].fd = subs.att_sp_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /** --- ACTUATOR OUTPUTS --- */ - subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); - fds[fdsc_count].fd = subs.act_0_sub; + /* --- ACTUATOR OUTPUTS --- */ + subs.act_outputs_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); + fds[fdsc_count].fd = subs.act_outputs_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ACTUATOR CONTROL VALUE --- */ - /* subscribe to ORB for actuator control */ - subs.controls_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); - fds[fdsc_count].fd = subs.controls_0_sub; + subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + fds[fdsc_count].fd = subs.act_controls_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ - /* subscribe to ORB for actuator control */ - subs.controls_effective_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); - fds[fdsc_count].fd = subs.controls_effective_0_sub; + subs.act_controls_effective_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); + fds[fdsc_count].fd = subs.act_controls_effective_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- LOCAL POSITION --- */ - /* subscribe to ORB for local position */ subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); fds[fdsc_count].fd = subs.local_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- GLOBAL POSITION --- */ - /* subscribe to ORB for global position */ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); fds[fdsc_count].fd = subs.global_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- VICON POSITION --- */ - /* subscribe to ORB for vicon position */ subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position)); fds[fdsc_count].fd = subs.vicon_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- FLOW measurements --- */ - /* subscribe to ORB for flow measurements */ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); fds[fdsc_count].fd = subs.flow_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- BATTERY STATUS --- */ - /* subscribe to ORB for flow measurements */ subs.batt_sub = orb_subscribe(ORB_ID(battery_status)); fds[fdsc_count].fd = subs.batt_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- DIFFERENTIAL PRESSURE --- */ - /* subscribe to ORB for flow measurements */ - subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); - fds[fdsc_count].fd = subs.diff_pres_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - - /* --- AIRSPEED --- */ - /* subscribe to ORB for airspeed */ - subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed)); - fds[fdsc_count].fd = subs.airspeed_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - /* WARNING: If you get the error message below, * then the number of registered messages (fdsc) * differs from the number of messages in the above list. @@ -625,7 +604,7 @@ int sdlog2_thread_main(int argc, char *argv[]) * set up poll to block for new data, * wait for a maximum of 1000 ms (1 second) */ - // const int timeout = 1000; + const int poll_timeout = 1000; thread_running = true; @@ -641,13 +620,17 @@ int sdlog2_thread_main(int argc, char *argv[]) starttime = hrt_absolute_time(); - /* track skipping */ - int skip_count = 0; + /* track changes in sensor_combined topic */ + uint16_t gyro_counter = 0; + uint16_t accelerometer_counter = 0; + uint16_t magnetometer_counter = 0; + uint16_t baro_counter = 0; + uint16_t differential_pressure_counter = 0; while (!thread_should_exit) { /* poll all topics */ - int poll_ret = poll(fds, 4, 1000); + int poll_ret = poll(fds, fdsc, poll_timeout); /* handle the poll result */ if (poll_ret == 0) { @@ -666,11 +649,11 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_lock(&logbuffer_mutex); /* write time stamp message */ - log_msg.msg_type = LOG_TS_MSG; - log_msg.body.log_TS.t = hrt_absolute_time(); - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TS)); + log_msg.msg_type = LOG_TIME_MSG; + log_msg.body.log_TIME.t = hrt_absolute_time(); + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TIME)); - /* --- VEHICLE COMMAND VALUE --- */ + /* --- VEHICLE COMMAND --- */ if (fds[ifds++].revents & POLLIN) { /* copy command into local buffer */ orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); @@ -680,19 +663,58 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet } - /* --- SENSORS RAW VALUE --- */ + /* --- SENSOR COMBINED --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw); - log_msg.msg_type = LOG_RAW_MSG; - log_msg.body.log_RAW.accX = buf.raw.accelerometer_m_s2[0]; - log_msg.body.log_RAW.accY = buf.raw.accelerometer_m_s2[1]; - log_msg.body.log_RAW.accZ = buf.raw.accelerometer_m_s2[2]; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(RAW)); + orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor); + bool write_IMU = false; + bool write_SENS = false; + if (buf.sensor.gyro_counter != gyro_counter) { + gyro_counter = buf.sensor.gyro_counter; + write_IMU = true; + } + if (buf.sensor.accelerometer_counter != accelerometer_counter) { + accelerometer_counter = buf.sensor.accelerometer_counter; + write_IMU = true; + } + if (buf.sensor.magnetometer_counter != magnetometer_counter) { + magnetometer_counter = buf.sensor.magnetometer_counter; + write_IMU = true; + } + if (buf.sensor.baro_counter != baro_counter) { + baro_counter = buf.sensor.baro_counter; + write_SENS = true; + } + if (buf.sensor.differential_pressure_counter != differential_pressure_counter) { + differential_pressure_counter = buf.sensor.differential_pressure_counter; + write_SENS = true; + } + if (write_IMU) { + log_msg.msg_type = LOG_IMU_MSG; + log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0]; + log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1]; + log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2]; + log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0]; + log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1]; + log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2]; + log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0]; + log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1]; + log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); + } + if (write_SENS) { + log_msg.msg_type = LOG_SENS_MSG; + log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar; + log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter; + log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius; + log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(SENS)); + } } - /* --- ATTITUDE VALUE --- */ + /* --- ATTITUDE --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att); log_msg.msg_type = LOG_ATT_MSG; @@ -702,69 +724,72 @@ int sdlog2_thread_main(int argc, char *argv[]) sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); } - /* --- ATTITUDE SETPOINT VALUE --- */ + /* --- ATTITUDE SETPOINT --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp); - // TODO not implemented yet + log_msg.msg_type = LOG_ATSP_MSG; + log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body; + log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body; + log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATSP)); } /* --- ACTUATOR OUTPUTS --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs); // TODO not implemented yet } - /* --- ACTUATOR CONTROL VALUE --- */ + /* --- ACTUATOR CONTROL --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls); // TODO not implemented yet } - /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* --- ACTUATOR CONTROL EFFECTIVE --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, subs.act_controls_effective_sub, &buf.act_controls_effective); // TODO not implemented yet } /* --- LOCAL POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet + orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos); + log_msg.msg_type = LOG_LPOS_MSG; + log_msg.body.log_LPOS.x = buf.local_pos.x; + log_msg.body.log_LPOS.y = buf.local_pos.y; + log_msg.body.log_LPOS.z = buf.local_pos.z; + log_msg.body.log_LPOS.vx = buf.local_pos.vx; + log_msg.body.log_LPOS.vy = buf.local_pos.vy; + log_msg.body.log_LPOS.vz = buf.local_pos.vz; + log_msg.body.log_LPOS.hdg = buf.local_pos.hdg; + log_msg.body.log_LPOS.home_lat = buf.local_pos.home_lat; + log_msg.body.log_LPOS.home_lon = buf.local_pos.home_lon; + log_msg.body.log_LPOS.home_alt = buf.local_pos.home_alt; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(LPOS)); } /* --- GLOBAL POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos); // TODO not implemented yet } /* --- VICON POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos); // TODO not implemented yet } - /* --- FLOW measurements --- */ + /* --- FLOW --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow); // TODO not implemented yet } /* --- BATTERY STATUS --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet - } - - /* --- DIFFERENTIAL PRESSURE --- */ - if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet - } - - /* --- AIRSPEED --- */ - if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt); // TODO not implemented yet } diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h index bbf8b6f12f..59b91d90db 100644 --- a/src/modules/sdlog2/sdlog2_format.h +++ b/src/modules/sdlog2/sdlog2_format.h @@ -93,6 +93,6 @@ struct log_format_s { #define LOG_FORMAT_MSG 0x80 -#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) +#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s) #endif /* SDLOG2_FORMAT_H_ */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index ae98ea0381..0bc999e243 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -47,13 +47,13 @@ /* define message formats */ -/* === 1: TS - TIME STAMP === */ -#define LOG_TS_MSG 1 -struct log_TS_s { +/* --- TIME - TIME STAMP --- */ +#define LOG_TIME_MSG 1 +struct log_TIME_s { uint64_t t; }; -/* === 2: ATT - ATTITUDE === */ +/* --- ATT - ATTITUDE --- */ #define LOG_ATT_MSG 2 struct log_ATT_s { float roll; @@ -61,20 +61,71 @@ struct log_ATT_s { float yaw; }; -/* === 3: RAW - SENSORS === */ -#define LOG_RAW_MSG 3 -struct log_RAW_s { - float accX; - float accY; - float accZ; +/* --- ATSP - ATTITUDE SET POINT --- */ +#define LOG_ATSP_MSG 3 +struct log_ATSP_s { + float roll_sp; + float pitch_sp; + float yaw_sp; +}; + +/* --- IMU - IMU SENSORS --- */ +#define LOG_IMU_MSG 4 +struct log_IMU_s { + float acc_x; + float acc_y; + float acc_z; + float gyro_x; + float gyro_y; + float gyro_z; + float mag_x; + float mag_y; + float mag_z; +}; + +/* --- SENS - OTHER SENSORS --- */ +#define LOG_SENS_MSG 5 +struct log_SENS_s { + float baro_pres; + float baro_alt; + float baro_temp; + float diff_pres; +}; + +/* --- LPOS - LOCAL POSITION --- */ +#define LOG_LPOS_MSG 6 +struct log_LPOS_s { + float x; + float y; + float z; + float vx; + float vy; + float vz; + float hdg; + int32_t home_lat; + int32_t home_lon; + float home_alt; +}; + +/* --- LPOS - LOCAL POSITION SETPOINT --- */ +#define LOG_LPSP_MSG 7 +struct log_LPSP_s { + float x; + float y; + float z; + float yaw; }; /* construct list of all message formats */ static const struct log_format_s log_formats[] = { - LOG_FORMAT(TS, "Q", "t"), - LOG_FORMAT(ATT, "fff", "roll,pitch,yaw"), - LOG_FORMAT(RAW, "fff", "accX,accY,accZ"), + LOG_FORMAT(TIME, "Q", "t"), + LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"), + LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), + LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), + LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), + LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), + LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From 2876bc72f979b4596fbe97cfae71c0d04d4753b2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 28 May 2013 17:46:24 +0200 Subject: [PATCH 46/89] Slightly reworked IO internal failsafe, added command to activate it (px4io failsafe), does not parse commandline arguments yet --- src/drivers/px4io/px4io.cpp | 52 +++++++++++++++++++++++---- src/modules/px4iofirmware/mixer.cpp | 29 +++++++++++---- src/modules/px4iofirmware/protocol.h | 4 ++- src/modules/px4iofirmware/registers.c | 3 +- 4 files changed, 73 insertions(+), 15 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 8b2fae12b8..f25d471aa0 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -106,7 +106,7 @@ public: * @param rate The rate in Hz actuator outpus are sent to IO. * Min 10 Hz, max 400 Hz */ - int set_update_rate(int rate); + int set_update_rate(int rate); /** * Set the battery current scaling and bias @@ -114,7 +114,15 @@ public: * @param amp_per_volt * @param amp_bias */ - void set_battery_current_scaling(float amp_per_volt, float amp_bias); + void set_battery_current_scaling(float amp_per_volt, float amp_bias); + + /** + * Push failsafe values to IO. + * + * @param vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full) + * @param len Number of channels, could up to 8 + */ + int set_failsafe_values(const uint16_t *vals, unsigned len); /** * Print the current status of IO @@ -326,11 +334,11 @@ PX4IO::PX4IO() : _to_actuators_effective(0), _to_outputs(0), _to_battery(0), + _primary_pwm_device(false), _battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor _battery_amp_bias(0), _battery_mamphour_total(0), - _battery_last_timestamp(0), - _primary_pwm_device(false) + _battery_last_timestamp(0) { /* we need this potentially before it could be set in task_main */ g_dev = this; @@ -689,6 +697,21 @@ PX4IO::io_set_control_state() return io_reg_set(PX4IO_PAGE_CONTROLS, 0, regs, _max_controls); } +int +PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len) +{ + uint16_t regs[_max_actuators]; + + unsigned max = (len < _max_actuators) ? len : _max_actuators; + + /* set failsafe values */ + for (unsigned i = 0; i < max; i++) + regs[i] = FLOAT_TO_REG(vals[i]); + + /* copy values to registers in IO */ + return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, regs, max); +} + int PX4IO::io_set_arming_state() { @@ -1250,7 +1273,7 @@ PX4IO::print_status() printf("%u bytes free\n", io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM)); uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS); - printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s\n", + printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n", flags, ((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""), ((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""), @@ -1262,7 +1285,8 @@ PX4IO::print_status() ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PPM" : ""), ((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"), ((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"), - ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL")); + ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"), + ((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : "")); uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS); printf("alarms 0x%04x%s%s%s%s%s%s%s\n", alarms, @@ -1718,6 +1742,20 @@ px4io_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "failsafe")) { + + /* XXX parse arguments here */ + + if (g_dev != nullptr) { + /* XXX testing values */ + uint16_t failsafe[4] = {1500, 1500, 1200, 1200}; + g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0])); + } else { + errx(1, "not loaded"); + } + exit(0); + } + if (!strcmp(argv[1], "recovery")) { if (g_dev != nullptr) { @@ -1845,5 +1883,5 @@ px4io_main(int argc, char *argv[]) monitor(); out: - errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current' or 'update'"); + errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe' or 'update'"); } diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 1234e2eea5..448d2355fc 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -102,13 +102,16 @@ mixer_tick(void) r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK; } + /* default to failsafe mixing */ source = MIX_FAILSAFE; /* * Decide which set of controls we're using. */ - if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) || - !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) { + + /* do not mix if mixer is invalid or if RAW_PWM mode is on and FMU is good */ + if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) && + !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) { /* don't actually mix anything - we already have raw PWM values or not a valid mixer. */ @@ -117,6 +120,7 @@ mixer_tick(void) } else { if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) && + (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) { /* mix from FMU controls */ @@ -132,15 +136,29 @@ mixer_tick(void) } } + /* + * Set failsafe status flag depending on mixing source + */ + if (source == MIX_FAILSAFE) { + r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE; + } else { + r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE); + } + /* * Run the mixers. */ if (source == MIX_FAILSAFE) { /* copy failsafe values to the servo outputs */ - for (unsigned i = 0; i < IO_SERVO_COUNT; i++) + for (unsigned i = 0; i < IO_SERVO_COUNT; i++) { r_page_servos[i] = r_page_servo_failsafe[i]; + /* safe actuators for FMU feedback */ + r_page_actuators[i] = (r_page_servos[i] - 1500) / 600.0f; + } + + } else if (source != MIX_NONE) { float outputs[IO_SERVO_COUNT]; @@ -156,7 +174,7 @@ mixer_tick(void) r_page_actuators[i] = FLOAT_TO_REG(outputs[i]); /* scale to servo output */ - r_page_servos[i] = (outputs[i] * 500.0f) + 1500; + r_page_servos[i] = (outputs[i] * 600.0f) + 1500; } for (unsigned i = mixed; i < IO_SERVO_COUNT; i++) @@ -175,7 +193,7 @@ mixer_tick(void) bool should_arm = ( /* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) && - /* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) && + /* there is valid input via direct PWM or mixer */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) && /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) && /* FMU is available or FMU is not available but override is an option */ ((r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) || (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) )) @@ -225,7 +243,6 @@ mixer_callback(uintptr_t handle, case MIX_FAILSAFE: case MIX_NONE: - /* XXX we could allow for configuration of per-output failsafe values */ return -1; } diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index e575bd8412..674f9dddd6 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -85,7 +85,7 @@ #define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */ #define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */ #define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */ -#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* harcoded # of relay outputs */ +#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */ /* dynamic status page */ #define PX4IO_PAGE_STATUS 1 @@ -104,6 +104,7 @@ #define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */ #define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */ #define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */ +#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */ #define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */ #define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */ @@ -148,6 +149,7 @@ #define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */ #define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */ #define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */ +#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */ #define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */ #define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */ diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 9698a0f2fb..3abf56a18d 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -41,6 +41,7 @@ #include #include +#include #include @@ -179,7 +180,7 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE * * Failsafe servo PWM values */ -uint16_t r_page_servo_failsafe[IO_SERVO_COUNT]; +uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 }; void registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values) From f6570172da02bba79b5e050c6e02b86dc96551c9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 May 2013 17:07:26 +0200 Subject: [PATCH 47/89] Set default failsafe value to 0 of mixer --- src/drivers/px4io/px4io.cpp | 29 +++++++++++++++------ src/modules/px4iofirmware/mixer.cpp | 37 +++++++++++++++++++++++++++ src/modules/px4iofirmware/registers.c | 5 +++- 3 files changed, 62 insertions(+), 9 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index f25d471aa0..873d7eb82a 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -704,12 +704,8 @@ PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len) unsigned max = (len < _max_actuators) ? len : _max_actuators; - /* set failsafe values */ - for (unsigned i = 0; i < max; i++) - regs[i] = FLOAT_TO_REG(vals[i]); - /* copy values to registers in IO */ - return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, regs, max); + return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, vals, max); } int @@ -1744,11 +1740,28 @@ px4io_main(int argc, char *argv[]) if (!strcmp(argv[1], "failsafe")) { - /* XXX parse arguments here */ + if (argc < 3) { + errx(1, "failsafe command needs at least one channel value (ppm)"); + } if (g_dev != nullptr) { - /* XXX testing values */ - uint16_t failsafe[4] = {1500, 1500, 1200, 1200}; + + /* set values for first 8 channels, fill unassigned channels with 1500. */ + uint16_t failsafe[8]; + + for (int i = 0; i < sizeof(failsafe) / sizeof(failsafe[0]); i++) + { + /* set channel to commanline argument or to 900 for non-provided channels */ + if (argc > i + 2) { + failsafe[i] = atoi(argv[i+2]); + if (failsafe[i] < 800 || failsafe[i] > 2200) { + errx(1, "value out of range of 800 < value < 2200. Aborting."); + } + } else { + failsafe[i] = 1500; + } + } + g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0])); } else { errx(1, "not loaded"); diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 448d2355fc..0b8ed6dc59 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -85,6 +85,9 @@ static int mixer_callback(uintptr_t handle, static MixerGroup mixer_group(mixer_callback, 0); +/* Set the failsafe values of all mixed channels (based on zero throttle, controls centered) */ +static void mixer_set_failsafe(); + void mixer_tick(void) { @@ -243,6 +246,7 @@ mixer_callback(uintptr_t handle, case MIX_FAILSAFE: case MIX_NONE: + control = 0.0f; return -1; } @@ -320,8 +324,41 @@ mixer_handle_text(const void *buffer, size_t length) memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid); mixer_text_length = resid; + + /* update failsafe values */ + mixer_set_failsafe(); } break; } } + +static void +mixer_set_failsafe() +{ + /* + * Check if a custom failsafe value has been written, + * else use the opportunity to set decent defaults. + */ + if (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) + return; + + float outputs[IO_SERVO_COUNT]; + unsigned mixed; + + /* mix */ + mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT); + + /* scale to PWM and update the servo outputs as required */ + for (unsigned i = 0; i < mixed; i++) { + + /* scale to servo output */ + r_page_servo_failsafe[i] = (outputs[i] * 600.0f) + 1500; + + } + + /* disable the rest of the outputs */ + for (unsigned i = mixed; i < IO_SERVO_COUNT; i++) + r_page_servo_failsafe[i] = 0; + +} diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 3abf56a18d..49a7233528 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -231,11 +231,14 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num case PX4IO_PAGE_FAILSAFE_PWM: /* copy channel data */ - while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) { + while ((offset < IO_SERVO_COUNT) && (num_values > 0)) { /* XXX range-check value? */ r_page_servo_failsafe[offset] = *values; + /* flag the failsafe values as custom */ + r_setup_arming |= PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM; + offset++; num_values--; values++; From 5f2571dd01c90ba1209d263c52d818225644ce07 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 May 2013 18:29:41 +0200 Subject: [PATCH 48/89] Set unknown channels to zero, since centering them is a slightly dangerous guess --- src/drivers/px4io/px4io.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 873d7eb82a..0a31831f09 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1758,7 +1758,8 @@ px4io_main(int argc, char *argv[]) errx(1, "value out of range of 800 < value < 2200. Aborting."); } } else { - failsafe[i] = 1500; + /* a zero value will result in stopping to output any pulse */ + failsafe[i] = 0; } } From abb024c724435937c1a0ae707dccfa28a48ef559 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 May 2013 18:32:23 +0200 Subject: [PATCH 49/89] More safety added by disabling pulses --- src/modules/px4iofirmware/registers.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 49a7233528..df7d6dcd35 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -179,8 +179,10 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE * PAGE 105 * * Failsafe servo PWM values + * + * Disable pulses as default. */ -uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 }; +uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 0 }; void registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values) From d6ae0461ab5c89f87ac10a2304d55a893d0f72f9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 12:28:05 +0400 Subject: [PATCH 50/89] sdlog2: GPS message added --- src/modules/sdlog2/sdlog2.c | 15 ++++++++++++++- src/modules/sdlog2/sdlog2_messages.h | 21 +++++++++++++++++++-- 2 files changed, 33 insertions(+), 3 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 48d107945b..8aa4db9348 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -504,6 +504,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_SENS_s log_SENS; struct log_LPOS_s log_LPOS; struct log_LPSP_s log_LPSP; + struct log_GPS_s log_GPS; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -663,7 +664,19 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet + log_msg.msg_type = LOG_GPS_MSG; + log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec; + log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type; + log_msg.body.log_GPS.satellites_visible = buf.gps_pos.satellites_visible; + log_msg.body.log_GPS.lat = buf.gps_pos.lat; + log_msg.body.log_GPS.lon = buf.gps_pos.lon; + log_msg.body.log_GPS.alt = buf.gps_pos.alt; + log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s; + log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s; + log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; + log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; + log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(GPS)); } /* --- SENSOR COMBINED --- */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 0bc999e243..3ff5978152 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -107,7 +107,7 @@ struct log_LPOS_s { float home_alt; }; -/* --- LPOS - LOCAL POSITION SETPOINT --- */ +/* --- LPSP - LOCAL POSITION SETPOINT --- */ #define LOG_LPSP_MSG 7 struct log_LPSP_s { float x; @@ -116,16 +116,33 @@ struct log_LPSP_s { float yaw; }; +/* --- GPS - GPS POSITION --- */ +#define LOG_GPS_MSG 8 +struct log_GPS_s { + uint64_t gps_time; + uint8_t fix_type; + uint8_t satellites_visible; + int32_t lat; + int32_t lon; + float alt; + float vel_n; + float vel_e; + float vel_d; + float cog; + uint8_t vel_valid; +}; + /* construct list of all message formats */ static const struct log_format_s log_formats[] = { - LOG_FORMAT(TIME, "Q", "t"), + LOG_FORMAT(TIME, "Q", "StartTime"), LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"), LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), + LOG_FORMAT(GPS, "QBBLLfffffB", "GPSTime,FixType,Sats,Lat,Lon,Alt,VelN,VelE,VelD,Cog,VelValid"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From 9952fef645a04ca3b0d86dcb7bae203f27c77a03 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 21:27:55 +0400 Subject: [PATCH 51/89] sdlog2 messages packing fixed, sdlog2_dump.py now produces much more compressed output. --- Tools/sdlog2_dump.py | 51 ++++++++++++++++++++-------- src/modules/sdlog2/sdlog2_messages.h | 2 ++ 2 files changed, 38 insertions(+), 15 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index fa02a37237..e4a4e24250 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -50,6 +50,7 @@ class SDLog2Parser: __csv_delim = "," __csv_null = "" __msg_filter = [] + __time_msg = None __debug_out = False def __init__(self): @@ -63,6 +64,7 @@ class SDLog2Parser: self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns + self.__csv_updated = False self.__msg_filter_map = {} # filter in form of map, with '*" expanded to full list of fields def setCSVDelimiter(self, csv_delim): @@ -74,6 +76,9 @@ class SDLog2Parser: def setMsgFilter(self, msg_filter): self.__msg_filter = msg_filter + def setTimeMsg(self, time_msg): + self.__time_msg = time_msg + def setDebugOut(self, debug_out): self.__debug_out = debug_out @@ -115,7 +120,8 @@ class SDLog2Parser: self.__initCSV() first_data_msg = False self.__parseMsg(msg_descr) - + if not self.__debug_out and self.__time_msg != None and self.__csv_updated: + self.__printCSVRow() f.close() def __bytesLeft(self): @@ -140,7 +146,18 @@ class SDLog2Parser: self.__csv_columns.append(full_label) self.__csv_data[full_label] = None print self.__csv_delim.join(self.__csv_columns) - + + def __printCSVRow(self): + s = [] + for full_label in self.__csv_columns: + v = self.__csv_data[full_label] + if v == None: + v = self.__csv_null + else: + v = str(v) + s.append(v) + print self.__csv_delim.join(s) + def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] @@ -171,6 +188,9 @@ class SDLog2Parser: def __parseMsg(self, msg_descr): msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr + if not self.__debug_out and self.__time_msg != None and msg_name == self.__time_msg and self.__csv_updated: + self.__printCSVRow() + self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) @@ -193,31 +213,27 @@ class SDLog2Parser: label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "." + label] = data[i] - # format and print CSV row - s = [] - for full_label in self.__csv_columns: - v = self.__csv_data[full_label] - if v == None: - v = self.__csv_null - else: - v = str(v) - s.append(v) - print self.__csv_delim.join(s) + if self.__time_msg != None and msg_name != self.__time_msg: + self.__csv_updated = True + if self.__time_msg == None: + self.__printCSVRow() self.__ptr += msg_length def _main(): if len(sys.argv) < 2: - print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]]\n" + print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" print "\t-v\tUse plain debug output instead of CSV.\n" print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." + print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" return fn = sys.argv[1] debug_out = False msg_filter = [] csv_null = "" csv_delim = "," + time_msg = None opt = None for arg in sys.argv[2:]: if opt != None: @@ -225,7 +241,9 @@ def _main(): csv_delim = arg elif opt == "n": csv_null = arg - if opt == "m": + elif opt == "t": + time_msg = arg + elif opt == "m": show_fields = "*" a = arg.split(".") if len(a) > 1: @@ -241,13 +259,16 @@ def _main(): opt = "n" elif arg == "-m": opt = "m" - + elif arg == "-t": + opt = "t" + if csv_delim == "\\t": csv_delim = "\t" parser = SDLog2Parser() parser.setCSVDelimiter(csv_delim) parser.setCSVNull(csv_null) parser.setMsgFilter(msg_filter) + parser.setTimeMsg(time_msg) parser.setDebugOut(debug_out) parser.process(fn) diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 3ff5978152..2baccc106e 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -47,6 +47,7 @@ /* define message formats */ +#pragma pack(push, 1) /* --- TIME - TIME STAMP --- */ #define LOG_TIME_MSG 1 struct log_TIME_s { @@ -131,6 +132,7 @@ struct log_GPS_s { float cog; uint8_t vel_valid; }; +#pragma pack(pop) /* construct list of all message formats */ From b614d2f1eb3b3ddd26fa22a1a0761a5aef52c1a8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 23:41:06 +0400 Subject: [PATCH 52/89] adlog2: added options cleanup, updates rate limit added --- src/modules/sdlog2/sdlog2.c | 75 +++++++++++++++++++++++-------------- 1 file changed, 47 insertions(+), 28 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 8aa4db9348..2422a15f4c 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -152,14 +152,19 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - errx(1, "usage: sdlog2 {start|stop|status} [-s ]\n\n"); + errx(1, "usage: sdlog2 {start|stop|status} [-r ] -e -a\n" + "\t-r\tLog rate in Hz, 0 means unlimited rate\n" + "\t-e\tEnable logging by default (if not, can be started by command)\n" + "\t-a\tLog only when armed (can be still overriden by command)\n\n"); } unsigned long log_bytes_written = 0; -uint64_t starttime = 0; +uint64_t start_time = 0; /* logging on or off, default to true */ -bool logging_enabled = true; +bool logging_enabled = false; +bool log_when_armed = false; +useconds_t poll_delay = 0; /** * The sd log deamon app only briefly exists to start @@ -384,24 +389,26 @@ int sdlog2_thread_main(int argc, char *argv[]) argv += 2; int ch; - while ((ch = getopt(argc, argv, "s:r")) != EOF) { + while ((ch = getopt(argc, argv, "r:ea")) != EOF) { switch (ch) { - case 's': { - /* log only every n'th (gyro clocked) value */ - unsigned s = strtoul(optarg, NULL, 10); + case 'r': { + unsigned r = strtoul(optarg, NULL, 10); - if (s < 1 || s > 250) { - errx(1, "Wrong skip value of %d, out of range (1..250)\n", s); + if (r == 0) { + poll_delay = 0; } else { - skip_value = s; + poll_delay = 1000000 / r; } } break; - case 'r': - /* log only on request, disable logging per default */ - logging_enabled = false; + case 'e': + logging_enabled = true; + break; + + case 'a': + log_when_armed = true; break; case '?': @@ -493,7 +500,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } subs; /* log message buffer: header + body */ - #pragma pack(push, 1) +#pragma pack(push, 1) struct { LOG_PACKET_HEADER; union { @@ -509,7 +516,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } log_msg = { LOG_PACKET_HEADER_INIT(0) }; - #pragma pack(pop) +#pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); /* --- MANAGEMENT - LOGGING COMMAND --- */ @@ -619,7 +626,9 @@ int sdlog2_thread_main(int argc, char *argv[]) /* start logbuffer emptying thread */ pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); - starttime = hrt_absolute_time(); + /* initialize statistics counter */ + log_bytes_written = 0; + start_time = hrt_absolute_time(); /* track changes in sensor_combined topic */ uint16_t gyro_counter = 0; @@ -629,24 +638,23 @@ int sdlog2_thread_main(int argc, char *argv[]) uint16_t differential_pressure_counter = 0; while (!thread_should_exit) { + if (!logging_enabled) { + usleep(100000); + continue; + } /* poll all topics */ - int poll_ret = poll(fds, fdsc, poll_timeout); + int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); /* handle the poll result */ - if (poll_ret == 0) { - /* XXX this means none of our providers is giving us data - might be an error? */ - } else if (poll_ret < 0) { - /* XXX this is seriously bad - should be an emergency */ - } else { + if (poll_ret < 0) { + printf("ERROR: Poll error, stop logging\n"); + thread_should_exit = false; + + } else if (poll_ret > 0) { int ifds = 0; - if (!logging_enabled) { - usleep(100000); - continue; - } - pthread_mutex_lock(&logbuffer_mutex); /* write time stamp message */ @@ -684,26 +692,32 @@ int sdlog2_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor); bool write_IMU = false; bool write_SENS = false; + if (buf.sensor.gyro_counter != gyro_counter) { gyro_counter = buf.sensor.gyro_counter; write_IMU = true; } + if (buf.sensor.accelerometer_counter != accelerometer_counter) { accelerometer_counter = buf.sensor.accelerometer_counter; write_IMU = true; } + if (buf.sensor.magnetometer_counter != magnetometer_counter) { magnetometer_counter = buf.sensor.magnetometer_counter; write_IMU = true; } + if (buf.sensor.baro_counter != baro_counter) { baro_counter = buf.sensor.baro_counter; write_SENS = true; } + if (buf.sensor.differential_pressure_counter != differential_pressure_counter) { differential_pressure_counter = buf.sensor.differential_pressure_counter; write_SENS = true; } + if (write_IMU) { log_msg.msg_type = LOG_IMU_MSG; log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0]; @@ -717,6 +731,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); } + if (write_SENS) { log_msg.msg_type = LOG_SENS_MSG; log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar; @@ -815,6 +830,10 @@ int sdlog2_thread_main(int argc, char *argv[]) /* unlock, now the writer thread may run */ pthread_mutex_unlock(&logbuffer_mutex); } + + if (poll_delay > 0) { + usleep(poll_delay); + } } print_sdlog2_status(); @@ -841,7 +860,7 @@ int sdlog2_thread_main(int argc, char *argv[]) void print_sdlog2_status() { float mebibytes = log_bytes_written / 1024.0f / 1024.0f; - float seconds = ((float)(hrt_absolute_time() - starttime)) / 1000000.0f; + float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); } From 1bf8f7b47ec8dd8f2f494fe40f193b3d1712e025 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 13:18:03 +0400 Subject: [PATCH 53/89] sdlog2 performance increased, fixes and cleanup --- .../{sdlog2_ringbuffer.c => logbuffer.c} | 25 +- .../{sdlog2_ringbuffer.h => logbuffer.h} | 22 +- src/modules/sdlog2/module.mk | 2 +- src/modules/sdlog2/sdlog2.c | 490 ++++++++++++------ 4 files changed, 357 insertions(+), 182 deletions(-) rename src/modules/sdlog2/{sdlog2_ringbuffer.c => logbuffer.c} (85%) rename src/modules/sdlog2/{sdlog2_ringbuffer.h => logbuffer.h} (78%) diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.c b/src/modules/sdlog2/logbuffer.c similarity index 85% rename from src/modules/sdlog2/sdlog2_ringbuffer.c rename to src/modules/sdlog2/logbuffer.c index 022a183ba3..52eda649e0 100644 --- a/src/modules/sdlog2/sdlog2_ringbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -33,9 +33,9 @@ ****************************************************************************/ /** - * @file sdlog2_ringbuffer.c + * @file logbuffer.c * - * Ring FIFO buffer for binary data. + * Ring FIFO buffer for binary log data. * * @author Anton Babushkin */ @@ -43,9 +43,9 @@ #include #include -#include "sdlog2_ringbuffer.h" +#include "logbuffer.h" -void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size) +void logbuffer_init(struct logbuffer_s *lb, int size) { lb->size = size; lb->write_ptr = 0; @@ -53,7 +53,7 @@ void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size) lb->data = malloc(lb->size); } -int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb) +int logbuffer_free(struct logbuffer_s *lb) { int n = lb->read_ptr - lb->write_ptr - 1; @@ -64,7 +64,7 @@ int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb) return n; } -int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb) +int logbuffer_count(struct logbuffer_s *lb) { int n = lb->write_ptr - lb->read_ptr; @@ -75,12 +75,12 @@ int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb) return n; } -int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb) +int logbuffer_is_empty(struct logbuffer_s *lb) { return lb->read_ptr == lb->write_ptr; } -void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) +bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size) { // bytes available to write int available = lb->read_ptr - lb->write_ptr - 1; @@ -90,7 +90,7 @@ void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) if (size > available) { // buffer overflow - return; + return false; } char *c = (char *) ptr; @@ -109,9 +109,10 @@ void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) int p = size - n; // number of bytes to write memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p); lb->write_ptr = (lb->write_ptr + p) % lb->size; + return true; } -int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr) +int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part) { // bytes available to read int available = lb->write_ptr - lb->read_ptr; @@ -125,17 +126,19 @@ int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr) if (available > 0) { // read pointer is before write pointer, write all available bytes n = available; + *is_part = false; } else { // read pointer is after write pointer, write bytes from read_ptr to end n = lb->size - lb->read_ptr; + *is_part = true; } *ptr = &(lb->data[lb->read_ptr]); return n; } -void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n) +void logbuffer_mark_read(struct logbuffer_s *lb, int n) { lb->read_ptr = (lb->read_ptr + n) % lb->size; } diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.h b/src/modules/sdlog2/logbuffer.h similarity index 78% rename from src/modules/sdlog2/sdlog2_ringbuffer.h rename to src/modules/sdlog2/logbuffer.h index 287f56c34f..a1d29d33da 100644 --- a/src/modules/sdlog2/sdlog2_ringbuffer.h +++ b/src/modules/sdlog2/logbuffer.h @@ -33,9 +33,9 @@ ****************************************************************************/ /** - * @file sdlog2_ringbuffer.h + * @file logbuffer.h * - * Ring FIFO buffer for binary data. + * Ring FIFO buffer for binary log data. * * @author Anton Babushkin */ @@ -43,7 +43,9 @@ #ifndef SDLOG2_RINGBUFFER_H_ #define SDLOG2_RINGBUFFER_H_ -struct sdlog2_logbuffer { +#include + +struct logbuffer_s { // all pointers are in bytes int write_ptr; int read_ptr; @@ -51,18 +53,18 @@ struct sdlog2_logbuffer { char *data; }; -void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size); +void logbuffer_init(struct logbuffer_s *lb, int size); -int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb); +int logbuffer_free(struct logbuffer_s *lb); -int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb); +int logbuffer_count(struct logbuffer_s *lb); -int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb); +int logbuffer_is_empty(struct logbuffer_s *lb); -void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size); +bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size); -int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr); +int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part); -void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n); +void logbuffer_mark_read(struct logbuffer_s *lb, int n); #endif diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk index 5a9936635a..f531296880 100644 --- a/src/modules/sdlog2/module.mk +++ b/src/modules/sdlog2/module.mk @@ -40,4 +40,4 @@ MODULE_COMMAND = sdlog2 MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30" SRCS = sdlog2.c \ - sdlog2_ringbuffer.c + logbuffer.c diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 2422a15f4c..6f509b917a 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -60,6 +60,7 @@ #include #include +#include #include #include #include @@ -68,6 +69,7 @@ #include #include #include +#include #include #include #include @@ -80,40 +82,64 @@ #include -#include "sdlog2_ringbuffer.h" +#include "logbuffer.h" #include "sdlog2_format.h" #include "sdlog2_messages.h" +#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \ + log_msgs_written++; \ + } else { \ + log_msgs_skipped++; \ + /*printf("skip\n");*/ \ + } + +//#define SDLOG2_DEBUG + static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */ static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ -static const int LOG_BUFFER_SIZE = 2048; -static const int MAX_WRITE_CHUNK = 1024; +static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */ +static const int LOG_BUFFER_SIZE = 8192; +static const int MAX_WRITE_CHUNK = 512; +static const int MIN_BYTES_TO_WRITE = 512; static const char *mountpoint = "/fs/microsd"; int log_file = -1; int mavlink_fd = -1; -struct sdlog2_logbuffer lb; +struct logbuffer_s lb; /* mutex / condition to synchronize threads */ pthread_mutex_t logbuffer_mutex; pthread_cond_t logbuffer_cond; -/** - * System state vector log buffer writing - */ -static void *sdlog2_logbuffer_write_thread(void *arg); +char folder_path[64]; + +/* statistics counters */ +unsigned long log_bytes_written = 0; +uint64_t start_time = 0; +unsigned long log_msgs_written = 0; +unsigned long log_msgs_skipped = 0; + +/* current state of logging */ +bool logging_enabled = false; +/* enable logging on start (-e option) */ +bool log_on_start = false; +/* enable logging when armed (-a option) */ +bool log_when_armed = false; +/* delay = 1 / rate (rate defined by -r option) */ +useconds_t poll_delay = 0; + +/* helper flag to track system state changes */ +bool flag_system_armed = false; + +pthread_t logwriter_pthread = 0; /** - * Create the thread to write the system vector + * Log buffer writing thread. Open and close file here. */ -pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf); - -/** - * Write a header to log file: list of message formats - */ -void sdlog2_write_formats(int fd); +static void *logwriter_thread(void *arg); /** * SD log management function. @@ -128,26 +154,49 @@ int sdlog2_thread_main(int argc, char *argv[]); /** * Print the correct usage. */ -static void usage(const char *reason); +static void sdlog2_usage(const char *reason); -static int file_exist(const char *filename); +/** + * Print the current status. + */ +static void sdlog2_status(void); + +/** + * Start logging: create new file and start log writer thread. + */ +void sdlog2_start_log(); + +/** + * Stop logging: stop log writer thread and close log file. + */ +void sdlog2_stop_log(); + +/** + * Write a header to log file: list of message formats. + */ +void write_formats(int fd); + + +static bool file_exist(const char *filename); static int file_copy(const char *file_old, const char *file_new); static void handle_command(struct vehicle_command_s *cmd); -/** - * Print the current status. - */ -static void print_sdlog2_status(void); +static void handle_status(struct vehicle_status_s *cmd); /** - * Create folder for current logging session. + * Create folder for current logging session. Store folder name in 'log_folder'. */ -static int create_logfolder(char *folder_path); +static int create_logfolder(); + +/** + * Select first free log file name and open it. + */ +static int open_logfile(); static void -usage(const char *reason) +sdlog2_usage(const char *reason) { if (reason) fprintf(stderr, "%s\n", reason); @@ -158,16 +207,8 @@ usage(const char *reason) "\t-a\tLog only when armed (can be still overriden by command)\n\n"); } -unsigned long log_bytes_written = 0; -uint64_t start_time = 0; - -/* logging on or off, default to true */ -bool logging_enabled = false; -bool log_when_armed = false; -useconds_t poll_delay = 0; - /** - * The sd log deamon app only briefly exists to start + * The logger deamon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. * @@ -177,7 +218,7 @@ useconds_t poll_delay = 0; int sdlog2_main(int argc, char *argv[]) { if (argc < 1) - usage("missing command"); + sdlog2_usage("missing command"); if (!strcmp(argv[1], "start")) { @@ -191,7 +232,7 @@ int sdlog2_main(int argc, char *argv[]) deamon_task = task_spawn("sdlog2", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 30, - 4096, + 2048, sdlog2_thread_main, (const char **)argv); exit(0); @@ -208,7 +249,7 @@ int sdlog2_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - print_sdlog2_status(); + sdlog2_status(); } else { printf("\tsdlog2 not started\n"); @@ -217,20 +258,20 @@ int sdlog2_main(int argc, char *argv[]) exit(0); } - usage("unrecognized command"); + sdlog2_usage("unrecognized command"); exit(1); } -int create_logfolder(char *folder_path) +int create_logfolder() { /* make folder on sdcard */ - uint16_t foldernumber = 1; // start with folder 0001 + uint16_t folder_number = 1; // start with folder sess001 int mkdir_ret; /* look for the next folder that does not exist */ - while (foldernumber < MAX_NO_LOGFOLDER) { - /* set up file path: e.g. /mnt/sdcard/sensorfile0001.txt */ - sprintf(folder_path, "%s/session%04u", mountpoint, foldernumber); + while (folder_number <= MAX_NO_LOGFOLDER) { + /* set up folder path: e.g. /fs/microsd/sess001 */ + sprintf(folder_path, "%s/sess%03u", mountpoint, folder_number); mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO); /* the result is -1 if the folder exists */ @@ -256,7 +297,7 @@ int create_logfolder(char *folder_path) } else if (mkdir_ret == -1) { /* folder exists already */ - foldernumber++; + folder_number++; continue; } else { @@ -265,63 +306,126 @@ int create_logfolder(char *folder_path) } } - if (foldernumber >= MAX_NO_LOGFOLDER) { + if (folder_number >= MAX_NO_LOGFOLDER) { /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ - warn("all %d possible folders exist already", MAX_NO_LOGFOLDER); + warnx("all %d possible folders exist already.\n", MAX_NO_LOGFOLDER); return -1; } return 0; } -static void * -sdlog2_logbuffer_write_thread(void *arg) +int open_logfile() +{ + /* make folder on sdcard */ + uint16_t file_number = 1; // start with file log001 + + /* string to hold the path to the log */ + char path_buf[64] = ""; + + int fd = 0; + + /* look for the next file that does not exist */ + while (file_number <= MAX_NO_LOGFILE) { + /* set up file path: e.g. /fs/microsd/sess001/log001.bin */ + sprintf(path_buf, "%s/log%03u.bin", folder_path, file_number); + + if (file_exist(path_buf)) { + file_number++; + continue; + } + + fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC); + + if (fd == 0) { + errx(1, "opening %s failed.\n", path_buf); + } + + warnx("logging to: %s\n", path_buf); + + return fd; + } + + if (file_number > MAX_NO_LOGFILE) { + /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ + warn("all %d possible files exist already\n", MAX_NO_LOGFILE); + return -1; + } + + return 0; +} + +static void *logwriter_thread(void *arg) { /* set name */ - prctl(PR_SET_NAME, "sdlog2 microSD I/O", 0); + prctl(PR_SET_NAME, "sdlog2_writer", 0); - struct sdlog2_logbuffer *logbuf = (struct sdlog2_logbuffer *)arg; + struct logbuffer_s *logbuf = (struct logbuffer_s *)arg; + + int log_file = open_logfile(); + + /* write log messages formats */ + write_formats(log_file); int poll_count = 0; void *read_ptr; int n = 0; + bool should_wait = false; + bool is_part = false; - while (!thread_should_exit) { + while (!thread_should_exit && !logwriter_should_exit) { /* make sure threads are synchronized */ pthread_mutex_lock(&logbuffer_mutex); /* update read pointer if needed */ if (n > 0) { - sdlog2_logbuffer_mark_read(&lb, n); + logbuffer_mark_read(&lb, n); } /* only wait if no data is available to process */ - if (sdlog2_logbuffer_is_empty(logbuf)) { + if (should_wait) { /* blocking wait for new data at this line */ pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex); } /* only get pointer to thread-safe data, do heavy I/O a few lines down */ - n = sdlog2_logbuffer_get_ptr(logbuf, &read_ptr); + int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part); /* continue */ pthread_mutex_unlock(&logbuffer_mutex); - if (n > 0) { + if (available > 0) { /* do heavy IO here */ - if (n > MAX_WRITE_CHUNK) + if (available > MAX_WRITE_CHUNK) { n = MAX_WRITE_CHUNK; + } else { + n = available; + } + n = write(log_file, read_ptr, n); + should_wait = (n == available) && !is_part; +#ifdef SDLOG2_DEBUG + printf("%i wrote: %i of %i, is_part=%i, should_wait=%i\n", poll_count, n, available, (int)is_part, (int)should_wait); +#endif + + if (n < 0) { + thread_should_exit = true; + err(1, "error writing log file"); + } + if (n > 0) { log_bytes_written += n; } + + } else { + should_wait = true; } - if (poll_count % 100 == 0) { + if (poll_count % 10 == 0) { fsync(log_file); } @@ -329,12 +433,22 @@ sdlog2_logbuffer_write_thread(void *arg) } fsync(log_file); + close(log_file); return OK; } -pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) +void sdlog2_start_log() { + warnx("start logging.\n"); + + /* initialize statistics counter */ + log_bytes_written = 0; + start_time = hrt_absolute_time(); + log_msgs_written = 0; + log_msgs_skipped = 0; + + /* initialize log buffer emptying thread */ pthread_attr_t receiveloop_attr; pthread_attr_init(&receiveloop_attr); @@ -345,14 +459,39 @@ pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) pthread_attr_setstacksize(&receiveloop_attr, 2048); + logwriter_should_exit = false; pthread_t thread; - pthread_create(&thread, &receiveloop_attr, sdlog2_logbuffer_write_thread, logbuf); - return thread; + /* start log buffer emptying thread */ + if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) { + errx(1, "error creating logwriter thread\n"); + } + + logging_enabled = true; // XXX we have to destroy the attr at some point } -void sdlog2_write_formats(int fd) +void sdlog2_stop_log() +{ + warnx("stop logging.\n"); + + logging_enabled = true; + logwriter_should_exit = true; + + /* wake up write thread one last time */ + pthread_mutex_lock(&logbuffer_mutex); + pthread_cond_signal(&logbuffer_cond); + /* unlock, now the writer thread may return */ + pthread_mutex_unlock(&logbuffer_mutex); + + /* wait for write thread to return */ + (void)pthread_join(logwriter_pthread, NULL); + + sdlog2_status(); +} + + +void write_formats(int fd) { /* construct message format packet */ struct { @@ -378,7 +517,7 @@ int sdlog2_thread_main(int argc, char *argv[]) mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); if (mavlink_fd < 0) { - warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); + warnx("failed to open MAVLink log stream, start mavlink app first.\n"); } /* log every n'th value (skip three per default) */ @@ -404,7 +543,7 @@ int sdlog2_thread_main(int argc, char *argv[]) break; case 'e': - logging_enabled = true; + log_on_start = true; break; case 'a': @@ -423,39 +562,48 @@ int sdlog2_thread_main(int argc, char *argv[]) } default: - usage("unrecognized flag"); - errx(1, "exiting."); + sdlog2_usage("unrecognized flag"); + errx(1, "exiting\n"); } } - if (file_exist(mountpoint) != OK) { - errx(1, "logging mount point %s not present, exiting.", mountpoint); + if (!file_exist(mountpoint)) { + errx(1, "logging mount point %s not present, exiting.\n", mountpoint); } - char folder_path[64]; - - if (create_logfolder(folder_path)) - errx(1, "unable to create logging folder, exiting."); - - /* string to hold the path to the sensorfile */ - char path_buf[64] = ""; + if (create_logfolder()) + errx(1, "unable to create logging folder, exiting.\n"); /* only print logging path, important to find log file later */ - warnx("logging to directory %s\n", folder_path); + warnx("logging to directory %s.\n", folder_path); - /* set up file path: e.g. /mnt/sdcard/session0001/actuator_controls0.bin */ - sprintf(path_buf, "%s/%s.bin", folder_path, "log"); + /* logging control buffers and subscriptions */ + struct { + struct vehicle_command_s cmd; + struct vehicle_status_s status; + } buf_control; + memset(&buf_control, 0, sizeof(buf_control)); - if (0 == (log_file = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC))) { - errx(1, "opening %s failed.\n", path_buf); - } + struct { + int cmd_sub; + int status_sub; + } subs_control; - /* write log messages formats */ - sdlog2_write_formats(log_file); + /* file descriptors to wait for */ + struct pollfd fds_control[2]; + /* --- VEHICLE COMMAND --- */ + subs_control.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds_control[0].fd = subs_control.cmd_sub; + fds_control[0].events = POLLIN; + + /* --- VEHICLE STATUS --- */ + subs_control.status_sub = orb_subscribe(ORB_ID(vehicle_status)); + fds_control[1].fd = subs_control.status_sub; + fds_control[1].events = POLLIN; /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 13; + const ssize_t fdsc = 12; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -469,8 +617,8 @@ int sdlog2_thread_main(int argc, char *argv[]) struct actuator_outputs_s act_outputs; struct actuator_controls_s act_controls; struct actuator_controls_effective_s act_controls_effective; - struct vehicle_command_s cmd; struct vehicle_local_position_s local_pos; + struct vehicle_local_position_setpoint_s local_pos_sp; struct vehicle_global_position_s global_pos; struct vehicle_gps_position_s gps_pos; struct vehicle_vicon_position_s vicon_pos; @@ -482,7 +630,6 @@ int sdlog2_thread_main(int argc, char *argv[]) memset(&buf, 0, sizeof(buf)); struct { - int cmd_sub; int sensor_sub; int att_sub; int att_sp_sub; @@ -490,6 +637,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int act_controls_sub; int act_controls_effective_sub; int local_pos_sub; + int local_pos_sp_sub; int global_pos_sub; int gps_pos_sub; int vicon_pos_sub; @@ -519,33 +667,25 @@ int sdlog2_thread_main(int argc, char *argv[]) #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); - /* --- MANAGEMENT - LOGGING COMMAND --- */ - /* subscribe to ORB for vehicle command */ - subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); - fds[fdsc_count].fd = subs.cmd_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - /* --- GPS POSITION --- */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- SENSORS RAW VALUE --- */ + /* --- SENSORS COMBINED --- */ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); fds[fdsc_count].fd = subs.sensor_sub; - /* do not rate limit, instead use skip counter (aliasing on rate limit) */ fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ATTITUDE VALUE --- */ + /* --- ATTITUDE --- */ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); fds[fdsc_count].fd = subs.att_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ATTITUDE SETPOINT VALUE --- */ + /* --- ATTITUDE SETPOINT --- */ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); fds[fdsc_count].fd = subs.att_sp_sub; fds[fdsc_count].events = POLLIN; @@ -557,13 +697,13 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ACTUATOR CONTROL VALUE --- */ + /* --- ACTUATOR CONTROL --- */ subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); fds[fdsc_count].fd = subs.act_controls_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* --- ACTUATOR CONTROL EFFECTIVE --- */ subs.act_controls_effective_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); fds[fdsc_count].fd = subs.act_controls_effective_sub; fds[fdsc_count].events = POLLIN; @@ -575,6 +715,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; + /* --- LOCAL POSITION SETPOINT --- */ + subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + fds[fdsc_count].fd = subs.local_pos_sp_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* --- GLOBAL POSITION --- */ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); fds[fdsc_count].fd = subs.global_pos_sub; @@ -587,7 +733,7 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- FLOW measurements --- */ + /* --- OPTICAL FLOW --- */ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); fds[fdsc_count].fd = subs.flow_sub; fds[fdsc_count].events = POLLIN; @@ -610,26 +756,19 @@ int sdlog2_thread_main(int argc, char *argv[]) /* * set up poll to block for new data, - * wait for a maximum of 1000 ms (1 second) + * wait for a maximum of 1000 ms */ const int poll_timeout = 1000; thread_running = true; /* initialize log buffer with specified size */ - sdlog2_logbuffer_init(&lb, LOG_BUFFER_SIZE); + logbuffer_init(&lb, LOG_BUFFER_SIZE); /* initialize thread synchronization */ pthread_mutex_init(&logbuffer_mutex, NULL); pthread_cond_init(&logbuffer_cond, NULL); - /* start logbuffer emptying thread */ - pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); - - /* initialize statistics counter */ - log_bytes_written = 0; - start_time = hrt_absolute_time(); - /* track changes in sensor_combined topic */ uint16_t gyro_counter = 0; uint16_t accelerometer_counter = 0; @@ -637,19 +776,44 @@ int sdlog2_thread_main(int argc, char *argv[]) uint16_t baro_counter = 0; uint16_t differential_pressure_counter = 0; + /* enable logging on start if needed */ + if (log_on_start) + sdlog2_start_log(); + while (!thread_should_exit) { - if (!logging_enabled) { - usleep(100000); + /* poll control topics */ + int poll_control_ret = poll(fds_control, sizeof(fds_control) / sizeof(fds_control[0]), logging_enabled ? 0 : 500); + + /* handle the poll result */ + if (poll_control_ret < 0) { + warnx("ERROR: poll control topics error, stop logging.\n"); + thread_should_exit = true; continue; + + } else if (poll_control_ret > 0) { + /* --- VEHICLE COMMAND --- */ + if (fds[0].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_command), subs_control.cmd_sub, &buf_control.cmd); + handle_command(&buf_control.cmd); + } + + /* --- VEHICLE STATUS --- */ + if (fds[1].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_status), subs_control.status_sub, &buf_control.status); + handle_status(&buf_control.status); + } } - /* poll all topics */ + if (!logging_enabled) + continue; + + /* poll data topics */ int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); /* handle the poll result */ if (poll_ret < 0) { - printf("ERROR: Poll error, stop logging\n"); - thread_should_exit = false; + warnx("ERROR: poll error, stop logging.\n"); + thread_should_exit = true; } else if (poll_ret > 0) { @@ -660,14 +824,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* write time stamp message */ log_msg.msg_type = LOG_TIME_MSG; log_msg.body.log_TIME.t = hrt_absolute_time(); - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TIME)); - - /* --- VEHICLE COMMAND --- */ - if (fds[ifds++].revents & POLLIN) { - /* copy command into local buffer */ - orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); - handle_command(&buf.cmd); - } + LOGBUFFER_WRITE_AND_COUNT(TIME); /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { @@ -684,7 +841,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(GPS)); + LOGBUFFER_WRITE_AND_COUNT(GPS); } /* --- SENSOR COMBINED --- */ @@ -729,7 +886,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0]; log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1]; log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); + LOGBUFFER_WRITE_AND_COUNT(IMU); } if (write_SENS) { @@ -738,7 +895,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter; log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius; log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(SENS)); + LOGBUFFER_WRITE_AND_COUNT(SENS); } } @@ -749,7 +906,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATT.roll = buf.att.roll; log_msg.body.log_ATT.pitch = buf.att.pitch; log_msg.body.log_ATT.yaw = buf.att.yaw; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); + LOGBUFFER_WRITE_AND_COUNT(ATT); } /* --- ATTITUDE SETPOINT --- */ @@ -759,7 +916,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body; log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body; log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATSP)); + LOGBUFFER_WRITE_AND_COUNT(ATSP); } /* --- ACTUATOR OUTPUTS --- */ @@ -794,7 +951,18 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_LPOS.home_lat = buf.local_pos.home_lat; log_msg.body.log_LPOS.home_lon = buf.local_pos.home_lon; log_msg.body.log_LPOS.home_alt = buf.local_pos.home_alt; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(LPOS)); + LOGBUFFER_WRITE_AND_COUNT(LPOS); + } + + /* --- LOCAL POSITION SETPOINT --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp); + log_msg.msg_type = LOG_LPSP_MSG; + log_msg.body.log_LPSP.x = buf.local_pos_sp.x; + log_msg.body.log_LPSP.y = buf.local_pos_sp.y; + log_msg.body.log_LPSP.z = buf.local_pos_sp.z; + log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw; + LOGBUFFER_WRITE_AND_COUNT(LPSP); } /* --- GLOBAL POSITION --- */ @@ -822,7 +990,10 @@ int sdlog2_thread_main(int argc, char *argv[]) } /* signal the other thread new data, but not yet unlock */ - if (sdlog2_logbuffer_count(&lb) > (lb.size / 2)) { + if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { +#ifdef SDLOG2_DEBUG + printf("signal %i\n", logbuffer_count(&lb)); +#endif /* only request write if several packets can be written at once */ pthread_cond_signal(&logbuffer_cond); } @@ -836,42 +1007,34 @@ int sdlog2_thread_main(int argc, char *argv[]) } } - print_sdlog2_status(); - - /* wake up write thread one last time */ - pthread_mutex_lock(&logbuffer_mutex); - pthread_cond_signal(&logbuffer_cond); - /* unlock, now the writer thread may return */ - pthread_mutex_unlock(&logbuffer_mutex); - - /* wait for write thread to return */ - (void)pthread_join(logwriter_pthread, NULL); + if (logging_enabled) + sdlog2_stop_log(); pthread_mutex_destroy(&logbuffer_mutex); pthread_cond_destroy(&logbuffer_cond); - warnx("exiting.\n\n"); + warnx("exiting.\n"); thread_running = false; return 0; } -void print_sdlog2_status() +void sdlog2_status() { float mebibytes = log_bytes_written / 1024.0f / 1024.0f; float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; - warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); + warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.\n", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); } /** * @return 0 if file exists */ -int file_exist(const char *filename) +bool file_exist(const char *filename) { struct stat buffer; - return stat(filename, &buffer); + return stat(filename, &buffer) == 0; } int file_copy(const char *file_old, const char *file_new) @@ -881,7 +1044,7 @@ int file_copy(const char *file_old, const char *file_new) int ret = 0; if (source == NULL) { - warnx("failed opening input file to copy"); + warnx("failed opening input file to copy.\n"); return 1; } @@ -889,7 +1052,7 @@ int file_copy(const char *file_old, const char *file_new) if (target == NULL) { fclose(source); - warnx("failed to open output file to copy"); + warnx("failed to open output file to copy.\n"); return 1; } @@ -900,7 +1063,7 @@ int file_copy(const char *file_old, const char *file_new) ret = fwrite(buf, 1, nread, target); if (ret <= 0) { - warnx("error writing file"); + warnx("error writing file.\n"); ret = 1; break; } @@ -918,25 +1081,19 @@ void handle_command(struct vehicle_command_s *cmd) { /* result of the command */ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED; + int param; /* request to set different system mode */ switch (cmd->command) { case VEHICLE_CMD_PREFLIGHT_STORAGE: + param = (int)(cmd->param3); - if (((int)(cmd->param3)) == 1) { + if (param == 1) { + sdlog2_start_log(); - /* enable logging */ - mavlink_log_info(mavlink_fd, "[log] file:"); - mavlink_log_info(mavlink_fd, "logdir"); - logging_enabled = true; - } - - if (((int)(cmd->param3)) == 0) { - - /* disable logging */ - mavlink_log_info(mavlink_fd, "[log] stopped."); - logging_enabled = false; + } else if (param == 0) { + sdlog2_stop_log(); } break; @@ -945,5 +1102,18 @@ void handle_command(struct vehicle_command_s *cmd) /* silently ignore */ break; } - +} + +void handle_status(struct vehicle_status_s *status) +{ + if (log_when_armed && (status->flag_system_armed != flag_system_armed)) { + flag_system_armed = status->flag_system_armed; + + if (flag_system_armed) { + sdlog2_start_log(); + + } else { + sdlog2_stop_log(); + } + } } From 34d4d62acc132b8a28395c4ab943f6e424b999c6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 15:59:42 +0400 Subject: [PATCH 54/89] sdlog2 messages cleanup, fixes --- src/modules/sdlog2/sdlog2.c | 166 ++++++++++++++++++------------------ 1 file changed, 84 insertions(+), 82 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 6f509b917a..27efe2c62f 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -93,6 +93,12 @@ /*printf("skip\n");*/ \ } +#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \ + fds[fdsc_count].fd = subs.##_var##_sub; \ + fds[fdsc_count].events = POLLIN; \ + fdsc_count++; + + //#define SDLOG2_DEBUG static bool thread_should_exit = false; /**< Deamon exit flag */ @@ -129,7 +135,7 @@ bool log_on_start = false; /* enable logging when armed (-a option) */ bool log_when_armed = false; /* delay = 1 / rate (rate defined by -r option) */ -useconds_t poll_delay = 0; +useconds_t sleep_delay = 0; /* helper flag to track system state changes */ bool flag_system_armed = false; @@ -204,7 +210,7 @@ sdlog2_usage(const char *reason) errx(1, "usage: sdlog2 {start|stop|status} [-r ] -e -a\n" "\t-r\tLog rate in Hz, 0 means unlimited rate\n" "\t-e\tEnable logging by default (if not, can be started by command)\n" - "\t-a\tLog only when armed (can be still overriden by command)\n\n"); + "\t-a\tLog only when armed (can be still overriden by command)\n"); } /** @@ -217,7 +223,7 @@ sdlog2_usage(const char *reason) */ int sdlog2_main(int argc, char *argv[]) { - if (argc < 1) + if (argc < 2) sdlog2_usage("missing command"); if (!strcmp(argv[1], "start")) { @@ -308,7 +314,7 @@ int create_logfolder() if (folder_number >= MAX_NO_LOGFOLDER) { /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ - warnx("all %d possible folders exist already.\n", MAX_NO_LOGFOLDER); + warnx("all %d possible folders exist already.", MAX_NO_LOGFOLDER); return -1; } @@ -338,17 +344,18 @@ int open_logfile() fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC); if (fd == 0) { - errx(1, "opening %s failed.\n", path_buf); + errx(1, "opening %s failed.", path_buf); } - warnx("logging to: %s\n", path_buf); + warnx("logging to: %s", path_buf); + mavlink_log_info(mavlink_fd, "[sdlog2] logging to: %s", path_buf); return fd; } if (file_number > MAX_NO_LOGFILE) { /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ - warn("all %d possible files exist already\n", MAX_NO_LOGFILE); + warn("all %d possible files exist already", MAX_NO_LOGFILE); return -1; } @@ -409,7 +416,7 @@ static void *logwriter_thread(void *arg) should_wait = (n == available) && !is_part; #ifdef SDLOG2_DEBUG - printf("%i wrote: %i of %i, is_part=%i, should_wait=%i\n", poll_count, n, available, (int)is_part, (int)should_wait); + printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait); #endif if (n < 0) { @@ -440,7 +447,8 @@ static void *logwriter_thread(void *arg) void sdlog2_start_log() { - warnx("start logging.\n"); + warnx("start logging."); + mavlink_log_info(mavlink_fd, "[sdlog2] start logging"); /* initialize statistics counter */ log_bytes_written = 0; @@ -464,7 +472,7 @@ void sdlog2_start_log() /* start log buffer emptying thread */ if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) { - errx(1, "error creating logwriter thread\n"); + errx(1, "error creating logwriter thread"); } logging_enabled = true; @@ -473,7 +481,8 @@ void sdlog2_start_log() void sdlog2_stop_log() { - warnx("stop logging.\n"); + warnx("stop logging."); + mavlink_log_info(mavlink_fd, "[sdlog2] stop logging"); logging_enabled = true; logwriter_should_exit = true; @@ -517,7 +526,7 @@ int sdlog2_thread_main(int argc, char *argv[]) mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); if (mavlink_fd < 0) { - warnx("failed to open MAVLink log stream, start mavlink app first.\n"); + warnx("failed to open MAVLink log stream, start mavlink app first."); } /* log every n'th value (skip three per default) */ @@ -534,10 +543,10 @@ int sdlog2_thread_main(int argc, char *argv[]) unsigned r = strtoul(optarg, NULL, 10); if (r == 0) { - poll_delay = 0; + sleep_delay = 0; } else { - poll_delay = 1000000 / r; + sleep_delay = 1000000 / r; } } break; @@ -552,58 +561,37 @@ int sdlog2_thread_main(int argc, char *argv[]) case '?': if (optopt == 'c') { - warnx("Option -%c requires an argument.\n", optopt); + warnx("Option -%c requires an argument.", optopt); } else if (isprint(optopt)) { - warnx("Unknown option `-%c'.\n", optopt); + warnx("Unknown option `-%c'.", optopt); } else { - warnx("Unknown option character `\\x%x'.\n", optopt); + warnx("Unknown option character `\\x%x'.", optopt); } default: sdlog2_usage("unrecognized flag"); - errx(1, "exiting\n"); + errx(1, "exiting"); } } if (!file_exist(mountpoint)) { - errx(1, "logging mount point %s not present, exiting.\n", mountpoint); + errx(1, "logging mount point %s not present, exiting.", mountpoint); } if (create_logfolder()) - errx(1, "unable to create logging folder, exiting.\n"); + errx(1, "unable to create logging folder, exiting."); /* only print logging path, important to find log file later */ - warnx("logging to directory %s.\n", folder_path); - - /* logging control buffers and subscriptions */ - struct { - struct vehicle_command_s cmd; - struct vehicle_status_s status; - } buf_control; - memset(&buf_control, 0, sizeof(buf_control)); - - struct { - int cmd_sub; - int status_sub; - } subs_control; + warnx("logging to directory: %s", folder_path); /* file descriptors to wait for */ struct pollfd fds_control[2]; - /* --- VEHICLE COMMAND --- */ - subs_control.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); - fds_control[0].fd = subs_control.cmd_sub; - fds_control[0].events = POLLIN; - - /* --- VEHICLE STATUS --- */ - subs_control.status_sub = orb_subscribe(ORB_ID(vehicle_status)); - fds_control[1].fd = subs_control.status_sub; - fds_control[1].events = POLLIN; /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 12; + const ssize_t fdsc = 15; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -611,6 +599,8 @@ int sdlog2_thread_main(int argc, char *argv[]) /* warning! using union here to save memory, elements should be used separately! */ union { + struct vehicle_command_s cmd; + struct vehicle_status_s status; struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; @@ -630,6 +620,8 @@ int sdlog2_thread_main(int argc, char *argv[]) memset(&buf, 0, sizeof(buf)); struct { + int cmd_sub; + int status_sub; int sensor_sub; int att_sub; int att_sp_sub; @@ -667,6 +659,18 @@ int sdlog2_thread_main(int argc, char *argv[]) #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); + /* --- VEHICLE COMMAND --- */ + subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds[fdsc_count].fd = subs.cmd_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- VEHICLE STATUS --- */ + subs.status_sub = orb_subscribe(ORB_ID(vehicle_status)); + fds[fdsc_count].fd = subs.status_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* --- GPS POSITION --- */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; @@ -716,7 +720,7 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- LOCAL POSITION SETPOINT --- */ - subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + subs.local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); fds[fdsc_count].fd = subs.local_pos_sp_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; @@ -750,7 +754,7 @@ int sdlog2_thread_main(int argc, char *argv[]) * differs from the number of messages in the above list. */ if (fdsc_count > fdsc) { - warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.\n", __FILE__, __LINE__); + warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.", __FILE__, __LINE__); fdsc_count = fdsc; } @@ -781,44 +785,42 @@ int sdlog2_thread_main(int argc, char *argv[]) sdlog2_start_log(); while (!thread_should_exit) { - /* poll control topics */ - int poll_control_ret = poll(fds_control, sizeof(fds_control) / sizeof(fds_control[0]), logging_enabled ? 0 : 500); + /* decide use usleep() or blocking poll() */ + bool use_sleep = sleep_delay > 0 && logging_enabled; - /* handle the poll result */ - if (poll_control_ret < 0) { - warnx("ERROR: poll control topics error, stop logging.\n"); - thread_should_exit = true; - continue; - - } else if (poll_control_ret > 0) { - /* --- VEHICLE COMMAND --- */ - if (fds[0].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_command), subs_control.cmd_sub, &buf_control.cmd); - handle_command(&buf_control.cmd); - } - - /* --- VEHICLE STATUS --- */ - if (fds[1].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_status), subs_control.status_sub, &buf_control.status); - handle_status(&buf_control.status); - } - } - - if (!logging_enabled) - continue; - - /* poll data topics */ - int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); + /* poll all topics if logging enabled or only management (first 2) if not */ + int poll_ret = poll(fds, logging_enabled ? fdsc_count : 2, use_sleep ? 0 : poll_timeout); /* handle the poll result */ if (poll_ret < 0) { - warnx("ERROR: poll error, stop logging.\n"); + warnx("ERROR: poll error, stop logging."); thread_should_exit = true; } else if (poll_ret > 0) { + /* check all data subscriptions only if logging enabled, + * logging_enabled can be changed while checking vehicle_command and vehicle_status */ + bool check_data = logging_enabled; int ifds = 0; + /* --- VEHICLE COMMAND --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); + handle_command(&buf.cmd); + } + + /* --- VEHICLE STATUS --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf.status); + if (log_when_armed) { + handle_status(&buf.status); + } + } + + if (!logging_enabled || !check_data) { + continue; + } + pthread_mutex_lock(&logbuffer_mutex); /* write time stamp message */ @@ -992,7 +994,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* signal the other thread new data, but not yet unlock */ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { #ifdef SDLOG2_DEBUG - printf("signal %i\n", logbuffer_count(&lb)); + printf("signal %i", logbuffer_count(&lb)); #endif /* only request write if several packets can be written at once */ pthread_cond_signal(&logbuffer_cond); @@ -1002,8 +1004,8 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_unlock(&logbuffer_mutex); } - if (poll_delay > 0) { - usleep(poll_delay); + if (use_sleep) { + usleep(sleep_delay); } } @@ -1013,7 +1015,7 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_destroy(&logbuffer_mutex); pthread_cond_destroy(&logbuffer_cond); - warnx("exiting.\n"); + warnx("exiting."); thread_running = false; @@ -1025,7 +1027,7 @@ void sdlog2_status() float mebibytes = log_bytes_written / 1024.0f / 1024.0f; float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; - warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.\n", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); + warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); } /** @@ -1044,7 +1046,7 @@ int file_copy(const char *file_old, const char *file_new) int ret = 0; if (source == NULL) { - warnx("failed opening input file to copy.\n"); + warnx("failed opening input file to copy."); return 1; } @@ -1052,7 +1054,7 @@ int file_copy(const char *file_old, const char *file_new) if (target == NULL) { fclose(source); - warnx("failed to open output file to copy.\n"); + warnx("failed to open output file to copy."); return 1; } @@ -1063,7 +1065,7 @@ int file_copy(const char *file_old, const char *file_new) ret = fwrite(buf, 1, nread, target); if (ret <= 0) { - warnx("error writing file.\n"); + warnx("error writing file."); ret = 1; break; } @@ -1106,7 +1108,7 @@ void handle_command(struct vehicle_command_s *cmd) void handle_status(struct vehicle_status_s *status) { - if (log_when_armed && (status->flag_system_armed != flag_system_armed)) { + if (status->flag_system_armed != flag_system_armed) { flag_system_armed = status->flag_system_armed; if (flag_system_armed) { From 9f895d87cd159205cf1e66be49cc4b1f787b54ec Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 17:16:12 +0400 Subject: [PATCH 55/89] sdlog2 mavlink msg fix --- src/modules/sdlog2/sdlog2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 27efe2c62f..83bc338e2e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -348,7 +348,7 @@ int open_logfile() } warnx("logging to: %s", path_buf); - mavlink_log_info(mavlink_fd, "[sdlog2] logging to: %s", path_buf); + mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf); return fd; } From 606f68c890dfc15ca29262f6c7c2eff29c9dfec7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 20:40:56 +0400 Subject: [PATCH 56/89] sdlog2 GPS message changes --- src/modules/sdlog2/sdlog2.c | 6 +++--- src/modules/sdlog2/sdlog2_messages.h | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 83bc338e2e..b5821098ff 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -834,15 +834,15 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.msg_type = LOG_GPS_MSG; log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec; log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type; - log_msg.body.log_GPS.satellites_visible = buf.gps_pos.satellites_visible; + log_msg.body.log_GPS.eph = buf.gps_pos.eph_m; + log_msg.body.log_GPS.epv = buf.gps_pos.epv_m; log_msg.body.log_GPS.lat = buf.gps_pos.lat; log_msg.body.log_GPS.lon = buf.gps_pos.lon; - log_msg.body.log_GPS.alt = buf.gps_pos.alt; + log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001; log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s; log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s; log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; - log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; LOGBUFFER_WRITE_AND_COUNT(GPS); } diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 2baccc106e..316459b1e9 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -122,7 +122,8 @@ struct log_LPSP_s { struct log_GPS_s { uint64_t gps_time; uint8_t fix_type; - uint8_t satellites_visible; + float eph; + float epv; int32_t lat; int32_t lon; float alt; @@ -130,7 +131,6 @@ struct log_GPS_s { float vel_e; float vel_d; float cog; - uint8_t vel_valid; }; #pragma pack(pop) @@ -144,7 +144,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), - LOG_FORMAT(GPS, "QBBLLfffffB", "GPSTime,FixType,Sats,Lat,Lon,Alt,VelN,VelE,VelD,Cog,VelValid"), + LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From 1addb9f6c56f68f600acd4bdd609ef14697bda44 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 20:42:43 +0400 Subject: [PATCH 57/89] Fixed bug in UBX::configure_message_rate() --- src/drivers/gps/ubx.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index b3093b0f6f..f2e7ca67dc 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -739,7 +739,7 @@ UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) msg.msg_class = msg_class; msg.msg_id = msg_id; msg.rate = rate; - send_message(CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg)); + send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg)); } void From bd8bafb347e9b020ef78ffc2b534161d3c3b71bd Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 2 Jun 2013 10:43:39 +0400 Subject: [PATCH 58/89] sdlog2_dump.py: "recover from errors" option --- Tools/sdlog2_dump.py | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index e4a4e24250..e40d5c1b51 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -52,6 +52,7 @@ class SDLog2Parser: __msg_filter = [] __time_msg = None __debug_out = False + __correct_errors = False def __init__(self): return @@ -81,6 +82,9 @@ class SDLog2Parser: def setDebugOut(self, debug_out): self.__debug_out = debug_out + + def setCorrectErrors(self, correct_errors): + self.__correct_errors = correct_errors def process(self, fn): self.reset() @@ -90,6 +94,7 @@ class SDLog2Parser: self.__msg_filter_map[msg_name] = show_fields first_data_msg = True f = open(fn, "r") + bytes_read = 0 while True: chunk = f.read(self.BLOCK_SIZE) if len(chunk) == 0: @@ -100,7 +105,11 @@ class SDLog2Parser: head1 = ord(self.__buffer[self.__ptr]) head2 = ord(self.__buffer[self.__ptr+1]) if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): - raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + if self.__correct_errors: + self.__ptr += 1 + continue + else: + raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) msg_type = ord(self.__buffer[self.__ptr+2]) if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message @@ -120,6 +129,7 @@ class SDLog2Parser: self.__initCSV() first_data_msg = False self.__parseMsg(msg_descr) + bytes_read += self.__ptr if not self.__debug_out and self.__time_msg != None and self.__csv_updated: self.__printCSVRow() f.close() @@ -221,8 +231,9 @@ class SDLog2Parser: def _main(): if len(sys.argv) < 2: - print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" + print "Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" print "\t-v\tUse plain debug output instead of CSV.\n" + print "\t-e\tRecover from errors.\n" print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." @@ -230,6 +241,7 @@ def _main(): return fn = sys.argv[1] debug_out = False + correct_errors = False msg_filter = [] csv_null = "" csv_delim = "," @@ -253,6 +265,8 @@ def _main(): else: if arg == "-v": debug_out = True + elif arg == "-e": + correct_errors = True elif arg == "-d": opt = "d" elif arg == "-n": @@ -270,6 +284,7 @@ def _main(): parser.setMsgFilter(msg_filter) parser.setTimeMsg(time_msg) parser.setDebugOut(debug_out) + parser.setCorrectErrors(correct_errors) parser.process(fn) if __name__ == "__main__": From 6e5e1ff817d11d84b55b63dd482f3205e0899c55 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 2 Jun 2013 12:22:43 +0400 Subject: [PATCH 59/89] sdlog2_dump.py comments and version updated --- Tools/sdlog2_dump.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index e40d5c1b51..318f72971f 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -2,10 +2,12 @@ """Dump binary log generated by sdlog2 or APM as CSV -Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] +Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] -v Use plain debug output instead of CSV. + -e Recover from errors. + -d Use "delimiter" in CSV. Default is ",". -n Use "null" as placeholder for empty values in CSV. Default is empty. @@ -15,7 +17,7 @@ Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.fi Multiple -m options allowed.""" __author__ = "Anton Babushkin" -__version__ = "1.1" +__version__ = "1.2" import struct, sys From f435025d26f49d1d9069282aa72c7e1cb9201773 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 4 Jun 2013 00:10:58 +0200 Subject: [PATCH 60/89] Completed main implementation and debugging --- .../hott_telemetry/hott_telemetry_main.c | 3 + src/drivers/hott_telemetry/messages.c | 194 ++++++++++-------- src/drivers/hott_telemetry/messages.h | 1 + .../att_pos_estimator_ekf/KalmanNav.cpp | 4 +- src/modules/systemlib/geo/geo.c | 8 +- src/modules/systemlib/geo/geo.h | 16 ++ 6 files changed, 133 insertions(+), 93 deletions(-) diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c index 827cb862ad..4318244f81 100644 --- a/src/drivers/hott_telemetry/hott_telemetry_main.c +++ b/src/drivers/hott_telemetry/hott_telemetry_main.c @@ -138,6 +138,7 @@ recv_req_id(int uart, uint8_t *id) /* if we have a binary mode request */ if (mode != BINARY_MODE_REQUEST_ID) { + warnx("Non binary request ID detected: %d", mode); return ERROR; } @@ -232,6 +233,8 @@ hott_telemetry_thread_main(int argc, char *argv[]) } send_data(uart, buffer, size); + } else { + warnx("NOK"); } } diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c index feec8998c5..1d746506e0 100644 --- a/src/drivers/hott_telemetry/messages.c +++ b/src/drivers/hott_telemetry/messages.c @@ -40,8 +40,9 @@ #include "messages.h" #include +#include #include -#include +#include #include #include #include @@ -51,11 +52,17 @@ /* The board is very roughly 5 deg warmer than the surrounding air */ #define BOARD_TEMP_OFFSET_DEG 5 +#define ALT_OFFSET 500.0f + static int battery_sub = -1; static int gps_sub = -1; static int home_sub = -1; static int sensor_sub = -1; +static bool home_position_set = false; +static double home_lat = 0.0d; +static double home_lon = 0.0d; + void messages_init(void) { @@ -69,15 +76,18 @@ void build_eam_response(uint8_t *buffer, size_t *size) { /* get a local copy of the current sensor values */ - struct sensor_combined_s raw = { 0 }; + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); /* get a local copy of the battery data */ - struct battery_status_s battery = { 0 }; + struct battery_status_s battery; + memset(&battery, 0, sizeof(battery)); orb_copy(ORB_ID(battery_status), battery_sub, &battery); - struct eam_module_msg msg = { 0 }; + struct eam_module_msg msg; *size = sizeof(msg); + memset(&msg, 0, *size); msg.start = START_BYTE; msg.eam_sensor_id = EAM_SENSOR_ID; @@ -92,12 +102,7 @@ build_eam_response(uint8_t *buffer, size_t *size) msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; - // TODO: flight time - // TODO: climb rate - - msg.stop = STOP_BYTE; - memcpy(buffer, &msg, *size); } @@ -105,102 +110,113 @@ void build_gps_response(uint8_t *buffer, size_t *size) { /* get a local copy of the current sensor values */ - struct sensor_combined_s raw = { 0 }; + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); /* get a local copy of the battery data */ - struct vehicle_gps_position_s gps = { 0 }; + struct vehicle_gps_position_s gps; + memset(&gps, 0, sizeof(gps)); orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); struct gps_module_msg msg = { 0 }; *size = sizeof(msg); + memset(&msg, 0, *size); msg.start = START_BYTE; msg.sensor_id = GPS_SENSOR_ID; msg.sensor_text_id = GPS_SENSOR_TEXT_ID; - /* Current flight direction */ - msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); - - /* GPS speed */ - uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); - msg.gps_speed_L = (uint8_t)speed & 0xff; - msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; - - /* Get latitude in degrees, minutes and seconds */ - double lat = ((double)(gps.lat)) * 1e-7d; - - msg.latitude_ns = 0; - if (lat < 0) { - msg.latitude_ns = 1; - lat = -lat; - } - - int deg; - int min; - int sec; - convert_to_degrees_minutes_seconds(lat, °, &min, &sec); - - uint16_t lat_min = (uint16_t)(deg * 100 + min); - msg.latitude_min_L = (uint8_t)lat_min & 0xff; - msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff; - uint16_t lat_sec = (uint16_t)(sec); - msg.latitude_sec_L = (uint8_t)lat_sec & 0xff; - msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff; - - - /* Get longitude in degrees, minutes and seconds */ - double lon = ((double)(gps.lon)) * 1e-7d; - - msg.longitude_ew = 0; - if (lon < 0) { - msg.longitude_ew = 1; - lon = -lon; - } - - convert_to_degrees_minutes_seconds(lon, °, &min, &sec); - - uint16_t lon_min = (uint16_t)(deg * 100 + min); - msg.longitude_min_L = (uint8_t)lon_min & 0xff; - msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff; - uint16_t lon_sec = (uint16_t)(sec); - msg.longitude_sec_L = (uint8_t)lon_sec & 0xff; - msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; - - /* Altitude */ - uint16_t alt = (uint16_t)(gps.alt * 1e-3 + 500.0f); - msg.altitude_L = (uint8_t)alt & 0xff; - msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; - - /* Distance from home */ - bool updated; - orb_check(home_sub, &updated); - if (updated) { - /* get a local copy of the home position data */ - struct home_position_s home = { 0 }; - orb_copy(ORB_ID(home_position), home_sub, &home); - - uint16_t dist = (uint16_t)get_distance_to_next_waypoint( - (double)home.lat*1e-7, (double)home.lon*1e-7, lat, lon); - warnx("dist %d home.lat %3.6f home.lon %3.6f lat %3.6f lon %3.6f ", - dist, (double)home.lat*1e-7d, (double)home.lon*1e-7d, lat, lon); - msg.distance_L = (uint8_t)dist & 0xff; - msg.distance_H = (uint8_t)(dist >> 8) & 0xff; - - /* Direction back to home */ - uint16_t bearing = (uint16_t)get_bearing_to_next_waypoint( - (double)home.lat*1e-7, (double)home.lon*1e-7, lat, lon) * M_RAD_TO_DEG_F; - msg.home_direction = (uint8_t)bearing >> 1; - } - msg.gps_num_sat = gps.satellites_visible; /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */ msg.gps_fix_char = (uint8_t)(gps.fix_type + 48); msg.gps_fix = (uint8_t)(gps.fix_type + 48); - msg.stop = STOP_BYTE; + /* No point collecting more data if we don't have a 3D fix yet */ + if (gps.fix_type > 2) { + /* Current flight direction */ + msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); + /* GPS speed */ + uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); + msg.gps_speed_L = (uint8_t)speed & 0xff; + msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; + + /* Get latitude in degrees, minutes and seconds */ + double lat = ((double)(gps.lat))*1e-7d; + + /* Prepend N or S specifier */ + msg.latitude_ns = 0; + if (lat < 0) { + msg.latitude_ns = 1; + lat = abs(lat); + } + + int deg; + int min; + int sec; + convert_to_degrees_minutes_seconds(lat, °, &min, &sec); + + uint16_t lat_min = (uint16_t)(deg * 100 + min); + msg.latitude_min_L = (uint8_t)lat_min & 0xff; + msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff; + uint16_t lat_sec = (uint16_t)(sec); + msg.latitude_sec_L = (uint8_t)lat_sec & 0xff; + msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff; + + /* Get longitude in degrees, minutes and seconds */ + double lon = ((double)(gps.lon))*1e-7d; + + /* Prepend E or W specifier */ + msg.longitude_ew = 0; + if (lon < 0) { + msg.longitude_ew = 1; + lon = abs(lon); + } + + convert_to_degrees_minutes_seconds(lon, °, &min, &sec); + + uint16_t lon_min = (uint16_t)(deg * 100 + min); + msg.longitude_min_L = (uint8_t)lon_min & 0xff; + msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff; + uint16_t lon_sec = (uint16_t)(sec); + msg.longitude_sec_L = (uint8_t)lon_sec & 0xff; + msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; + + /* Altitude */ + uint16_t alt = (uint16_t)(gps.alt*1e-3 + ALT_OFFSET ); + msg.altitude_L = (uint8_t)alt & 0xff; + msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + + /* Get any (and probably only ever one) home_sub postion report */ + bool updated; + orb_check(home_sub, &updated); + if (updated) { + /* get a local copy of the home position data */ + struct home_position_s home; + memset(&home, 0, sizeof(home)); + orb_copy(ORB_ID(home_position), home_sub, &home); + + home_lat = ((double)(home.lat))*1e-7d; + home_lon = ((double)(home.lon))*1e-7d; + home_position_set = true; + } + + /* Distance from home */ + if (home_position_set) { + uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); + + msg.distance_L = (uint8_t)dist & 0xff; + msg.distance_H = (uint8_t)(dist >> 8) & 0xff; + + /* Direction back to home */ + uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F); + msg.home_direction = (uint8_t)bearing >> 1; + } + } + + msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); } @@ -210,6 +226,8 @@ convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec) *deg = (int)val; double delta = val - *deg; - *min = (int)(delta * 60.0); - *sec = (int)(delta * 3600.0); + const double min_d = delta * 60.0d; + *min = (int)min_d; + delta = min_d - *min; + *sec = (int)(delta * 10000.0d); } diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h index 5f7dd5c145..e6d5cc7239 100644 --- a/src/drivers/hott_telemetry/messages.h +++ b/src/drivers/hott_telemetry/messages.h @@ -189,6 +189,7 @@ struct gps_module_msg { void messages_init(void); void build_eam_response(uint8_t *buffer, size_t *size); void build_gps_response(uint8_t *buffer, size_t *size); +float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp index 4ef150da1e..c3836bdfab 100644 --- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp +++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp @@ -683,7 +683,8 @@ int KalmanNav::correctPos() // fault detetcion float beta = y.dot(S.inverse() * y); - if (beta > _faultPos.get()) { + static int counter = 0; + if (beta > _faultPos.get() && (counter % 10 == 0)) { printf("fault in gps: beta = %8.4f\n", (double)beta); printf("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n", double(y(0) / sqrtf(RPos(0, 0))), @@ -693,6 +694,7 @@ int KalmanNav::correctPos() double(y(4) / sqrtf(RPos(4, 4))), double(y(5) / sqrtf(RPos(5, 5)))); } + counter++; return ret_ok; } diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c index 6746e8ff36..3ac4bd168c 100644 --- a/src/modules/systemlib/geo/geo.c +++ b/src/modules/systemlib/geo/geo.c @@ -46,7 +46,7 @@ #include #include -#include +//#include #include #include #include @@ -185,12 +185,12 @@ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, dou double d_lat = lat_next_rad - lat_now_rad; double d_lon = lon_next_rad - lon_now_rad; - double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad); + double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0d) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad); double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a)); const double radius_earth = 6371000.0d; - - return radius_earth * c; + printf("DIST: %.4f\n", radius_earth * c); + return radius_earth * c; } __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next) diff --git a/src/modules/systemlib/geo/geo.h b/src/modules/systemlib/geo/geo.h index 0c0b5c533e..84097b49f7 100644 --- a/src/modules/systemlib/geo/geo.h +++ b/src/modules/systemlib/geo/geo.h @@ -82,8 +82,24 @@ __EXPORT void map_projection_project(double lat, double lon, float *x, float *y) */ __EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon); +/** + * Returns the distance to the next waypoint in meters. + * + * @param lat_now current position in degrees (47.1234567°, not 471234567°) + * @param lon_now current position in degrees (8.1234567°, not 81234567°) + * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°) + * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°) + */ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); +/** + * Returns the bearing to the next waypoint in radians. + * + * @param lat_now current position in degrees (47.1234567°, not 471234567°) + * @param lon_now current position in degrees (8.1234567°, not 81234567°) + * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°) + * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°) + */ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); __EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end); From 30d17cf0ba9da7587a2087674c37cda5399ab851 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 4 Jun 2013 00:18:23 +0200 Subject: [PATCH 61/89] Fix whitespace --- src/drivers/hott_telemetry/messages.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c index 1d746506e0..e10a22dc45 100644 --- a/src/drivers/hott_telemetry/messages.c +++ b/src/drivers/hott_telemetry/messages.c @@ -193,7 +193,7 @@ build_gps_response(uint8_t *buffer, size_t *size) bool updated; orb_check(home_sub, &updated); if (updated) { - /* get a local copy of the home position data */ + /* get a local copy of the home position data */ struct home_position_s home; memset(&home, 0, sizeof(home)); orb_copy(ORB_ID(home_position), home_sub, &home); @@ -205,7 +205,7 @@ build_gps_response(uint8_t *buffer, size_t *size) /* Distance from home */ if (home_position_set) { - uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); + uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); msg.distance_L = (uint8_t)dist & 0xff; msg.distance_H = (uint8_t)(dist >> 8) & 0xff; @@ -213,7 +213,7 @@ build_gps_response(uint8_t *buffer, size_t *size) /* Direction back to home */ uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F); msg.home_direction = (uint8_t)bearing >> 1; - } + } } msg.stop = STOP_BYTE; @@ -223,11 +223,11 @@ build_gps_response(uint8_t *buffer, size_t *size) void convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec) { - *deg = (int)val; + *deg = (int)val; - double delta = val - *deg; - const double min_d = delta * 60.0d; - *min = (int)min_d; - delta = min_d - *min; - *sec = (int)(delta * 10000.0d); + double delta = val - *deg; + const double min_d = delta * 60.0d; + *min = (int)min_d; + delta = min_d - *min; + *sec = (int)(delta * 10000.0d); } From 9374e4b1f221d571d56686d7d92ecb6cabcca8b6 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 4 Jun 2013 00:52:48 +0200 Subject: [PATCH 62/89] Formatting and comments --- src/drivers/hott_telemetry/messages.c | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c index e10a22dc45..369070f8c4 100644 --- a/src/drivers/hott_telemetry/messages.c +++ b/src/drivers/hott_telemetry/messages.c @@ -52,8 +52,6 @@ /* The board is very roughly 5 deg warmer than the surrounding air */ #define BOARD_TEMP_OFFSET_DEG 5 -#define ALT_OFFSET 500.0f - static int battery_sub = -1; static int gps_sub = -1; static int home_sub = -1; @@ -146,7 +144,7 @@ build_gps_response(uint8_t *buffer, size_t *size) /* Get latitude in degrees, minutes and seconds */ double lat = ((double)(gps.lat))*1e-7d; - /* Prepend N or S specifier */ + /* Set the N or S specifier */ msg.latitude_ns = 0; if (lat < 0) { msg.latitude_ns = 1; @@ -168,7 +166,7 @@ build_gps_response(uint8_t *buffer, size_t *size) /* Get longitude in degrees, minutes and seconds */ double lon = ((double)(gps.lon))*1e-7d; - /* Prepend E or W specifier */ + /* Set the E or W specifier */ msg.longitude_ew = 0; if (lon < 0) { msg.longitude_ew = 1; @@ -185,7 +183,7 @@ build_gps_response(uint8_t *buffer, size_t *size) msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; /* Altitude */ - uint16_t alt = (uint16_t)(gps.alt*1e-3 + ALT_OFFSET ); + uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f); msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; From 82c7e58122992aab2cf698951f9a33817cf1a050 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 4 Jun 2013 01:03:16 +0200 Subject: [PATCH 63/89] Removed some debugging code --- src/modules/systemlib/geo/geo.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c index 3ac4bd168c..6463e6489e 100644 --- a/src/modules/systemlib/geo/geo.c +++ b/src/modules/systemlib/geo/geo.c @@ -46,7 +46,7 @@ #include #include -//#include +#include #include #include #include @@ -189,7 +189,6 @@ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, dou double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a)); const double radius_earth = 6371000.0d; - printf("DIST: %.4f\n", radius_earth * c); return radius_earth * c; } From 45fe45fefa7cff5c9799037ee024671b4493ab85 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 4 Jun 2013 13:32:57 +0200 Subject: [PATCH 64/89] Better error handling for too large arguments --- src/drivers/px4io/px4io.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 0a31831f09..0934e614b3 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -702,10 +702,12 @@ PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len) { uint16_t regs[_max_actuators]; - unsigned max = (len < _max_actuators) ? len : _max_actuators; + if (len > _max_actuators) + /* fail with error */ + return E2BIG; /* copy values to registers in IO */ - return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, vals, max); + return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, vals, len); } int @@ -1763,7 +1765,10 @@ px4io_main(int argc, char *argv[]) } } - g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0])); + int ret = g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0])); + + if (ret != OK) + errx(ret, "failed setting failsafe values"); } else { errx(1, "not loaded"); } From de82295ab5307bca0fbd2266fdd1547386fa19a8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 4 Jun 2013 14:13:02 +0200 Subject: [PATCH 65/89] HOTFIX: Allow PWM command to correctly set ARM_OK flag --- src/systemcmds/pwm/pwm.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index ff733df52f..e150b5a74b 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -185,12 +185,18 @@ pwm_main(int argc, char *argv[]) const char *arg = argv[0]; argv++; if (!strcmp(arg, "arm")) { + /* tell IO that its ok to disable its safety with the switch */ + ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0); + if (ret != OK) + err(1, "PWM_SERVO_SET_ARM_OK"); + /* tell IO that the system is armed (it will output values if safety is off) */ ret = ioctl(fd, PWM_SERVO_ARM, 0); if (ret != OK) err(1, "PWM_SERVO_ARM"); continue; } if (!strcmp(arg, "disarm")) { + /* disarm, but do not revoke the SET_ARM_OK flag */ ret = ioctl(fd, PWM_SERVO_DISARM, 0); if (ret != OK) err(1, "PWM_SERVO_DISARM"); From 7ae2cf9d2de9a07249eccdcae10d3ac84794d0fc Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 4 Jun 2013 16:48:55 +0400 Subject: [PATCH 66/89] Minor sdlog2/logbuffer cleanup --- src/modules/sdlog2/logbuffer.c | 15 ++------------- src/modules/sdlog2/logbuffer.h | 2 -- 2 files changed, 2 insertions(+), 15 deletions(-) diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index 52eda649e0..4205bcf20d 100644 --- a/src/modules/sdlog2/logbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -53,17 +53,6 @@ void logbuffer_init(struct logbuffer_s *lb, int size) lb->data = malloc(lb->size); } -int logbuffer_free(struct logbuffer_s *lb) -{ - int n = lb->read_ptr - lb->write_ptr - 1; - - if (n < 0) { - n += lb->size; - } - - return n; -} - int logbuffer_count(struct logbuffer_s *lb) { int n = lb->write_ptr - lb->read_ptr; @@ -124,12 +113,12 @@ int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part) int n = 0; if (available > 0) { - // read pointer is before write pointer, write all available bytes + // read pointer is before write pointer, all available bytes can be read n = available; *is_part = false; } else { - // read pointer is after write pointer, write bytes from read_ptr to end + // read pointer is after write pointer, read bytes from read_ptr to end of the buffer n = lb->size - lb->read_ptr; *is_part = true; } diff --git a/src/modules/sdlog2/logbuffer.h b/src/modules/sdlog2/logbuffer.h index a1d29d33da..e9635e5e73 100644 --- a/src/modules/sdlog2/logbuffer.h +++ b/src/modules/sdlog2/logbuffer.h @@ -55,8 +55,6 @@ struct logbuffer_s { void logbuffer_init(struct logbuffer_s *lb, int size); -int logbuffer_free(struct logbuffer_s *lb); - int logbuffer_count(struct logbuffer_s *lb); int logbuffer_is_empty(struct logbuffer_s *lb); From 032f7d0b0e0bfb0cb5b77ebb8553cf3dc7ddda9b Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 4 Jun 2013 23:24:30 +0200 Subject: [PATCH 67/89] Fix syncing issue with receiver on startup. --- src/drivers/hott_telemetry/hott_telemetry_main.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c index 4318244f81..1d2bdd92ee 100644 --- a/src/drivers/hott_telemetry/hott_telemetry_main.c +++ b/src/drivers/hott_telemetry/hott_telemetry_main.c @@ -133,15 +133,14 @@ recv_req_id(int uart, uint8_t *id) if (poll(fds, 1, timeout_ms) > 0) { /* Get the mode: binary or text */ read(uart, &mode, sizeof(mode)); - /* Read the device ID being polled */ - read(uart, id, sizeof(*id)); /* if we have a binary mode request */ if (mode != BINARY_MODE_REQUEST_ID) { - warnx("Non binary request ID detected: %d", mode); return ERROR; } + /* Read the device ID being polled */ + read(uart, id, sizeof(*id)); } else { warnx("UART timeout on TX/RX port"); return ERROR; @@ -216,9 +215,15 @@ hott_telemetry_thread_main(int argc, char *argv[]) uint8_t buffer[MESSAGE_BUFFER_SIZE]; size_t size = 0; uint8_t id = 0; + bool connected = true; while (!thread_should_exit) { if (recv_req_id(uart, &id) == OK) { + if (!connected) { + connected = true; + warnx("OK"); + } + switch (id) { case EAM_SENSOR_ID: build_eam_response(buffer, &size); @@ -234,7 +239,8 @@ hott_telemetry_thread_main(int argc, char *argv[]) send_data(uart, buffer, size); } else { - warnx("NOK"); + connected = false; + warnx("syncing"); } } From 68931f38d56c82c67d7d01e4db3157fac5815258 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Jun 2013 15:04:49 +0200 Subject: [PATCH 68/89] HOTFIX: Added start / stop syntax to GPIO led command --- src/modules/gpio_led/gpio_led.c | 72 ++++++++++++++++++++++----------- 1 file changed, 49 insertions(+), 23 deletions(-) diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c index a80bf9cb83..43cbe74c74 100644 --- a/src/modules/gpio_led/gpio_led.c +++ b/src/modules/gpio_led/gpio_led.c @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -64,6 +65,7 @@ struct gpio_led_s { }; static struct gpio_led_s gpio_led_data; +static bool gpio_led_started = false; __EXPORT int gpio_led_main(int argc, char *argv[]); @@ -75,31 +77,54 @@ int gpio_led_main(int argc, char *argv[]) { int pin = GPIO_EXT_1; - if (argc > 1) { - if (!strcmp(argv[1], "-p")) { - if (!strcmp(argv[2], "1")) { - pin = GPIO_EXT_1; + if (argc < 2) { + errx(1, "no argument provided. Try 'start' or 'stop' [-p 1/2]"); - } else if (!strcmp(argv[2], "2")) { - pin = GPIO_EXT_2; + } else { + + /* START COMMAND HANDLING */ + if (!strcmp(argv[1], "start")) { + + if (argc > 2) { + if (!strcmp(argv[1], "-p")) { + if (!strcmp(argv[2], "1")) { + pin = GPIO_EXT_1; + + } else if (!strcmp(argv[2], "2")) { + pin = GPIO_EXT_2; + + } else { + warnx("[gpio_led] Unsupported pin: %s\n", argv[2]); + exit(1); + } + } + } + + memset(&gpio_led_data, 0, sizeof(gpio_led_data)); + gpio_led_data.pin = pin; + int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0); + + if (ret != 0) { + warnx("[gpio_led] Failed to queue work: %d\n", ret); + exit(1); } else { - printf("[gpio_led] Unsupported pin: %s\n", argv[2]); - exit(1); + gpio_led_started = true; } + + exit(0); + + /* STOP COMMAND HANDLING */ + + } else if (!strcmp(argv[1], "stop")) { + gpio_led_started = false; + + /* INVALID COMMAND */ + + } else { + errx(1, "unrecognized command '%s', only supporting 'start' or 'stop'", argv[1]); } } - - memset(&gpio_led_data, 0, sizeof(gpio_led_data)); - gpio_led_data.pin = pin; - int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0); - - if (ret != 0) { - printf("[gpio_led] Failed to queue work: %d\n", ret); - exit(1); - } - - exit(0); } void gpio_led_start(FAR void *arg) @@ -110,7 +135,7 @@ void gpio_led_start(FAR void *arg) priv->gpio_fd = open(GPIO_DEVICE_PATH, 0); if (priv->gpio_fd < 0) { - printf("[gpio_led] GPIO: open fail\n"); + warnx("[gpio_led] GPIO: open fail\n"); return; } @@ -125,11 +150,11 @@ void gpio_led_start(FAR void *arg) int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0); if (ret != 0) { - printf("[gpio_led] Failed to queue work: %d\n", ret); + warnx("[gpio_led] Failed to queue work: %d\n", ret); return; } - printf("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin); + warnx("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin); } void gpio_led_cycle(FAR void *arg) @@ -187,5 +212,6 @@ void gpio_led_cycle(FAR void *arg) priv->counter = 0; /* repeat cycle at 5 Hz*/ - work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000)); + if (gpio_led_started) + work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000)); } From 6537759dfc58117258610bb64d621da646d7d4ea Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Thu, 6 Jun 2013 21:28:40 +1000 Subject: [PATCH 69/89] Add detailed documentation for SO3 gains tuning. USB nsh has been removed. --- nuttx/configs/px4fmu/nsh/defconfig | 6 +-- .../attitude_estimator_so3_comp_main.cpp | 48 +++++++++++++++---- .../attitude_estimator_so3_comp_params.c | 11 ++++- 3 files changed, 50 insertions(+), 15 deletions(-) diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 94d99112e2..02e2243020 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=n +CONFIG_USART1_SERIAL_CONSOLE=y CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=n +CONFIG_DEV_CONSOLE=y CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_CONSOLE=n #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 9bb749cafb..3cbc62ea1d 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -57,6 +57,7 @@ static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ +static float dq0 = 0.0f, dq1 = 0.0f, dq2 = 0.0f, dq3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ static bool bFilterInit = false; @@ -170,7 +171,7 @@ float invSqrt(float number) { //! Using accelerometer, sense the gravity vector. //! Using magnetometer, sense yaw. -void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) +void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz) { float initialRoll, initialPitch; float cosRoll, sinRoll, cosPitch, sinPitch; @@ -218,7 +219,7 @@ void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) q3q3 = q3 * q3; } -void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { +void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; @@ -228,7 +229,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az //! unlikely happen. if(bFilterInit == false) { - MahonyAHRSinit(ax,ay,az,mx,my,mz); + NonlinearSO3AHRSinit(ax,ay,az,mx,my,mz); bFilterInit = true; } @@ -306,14 +307,25 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az gz += twoKp * halfez; } - // Integrate rate of change of quaternion + //! Integrate rate of change of quaternion +#if 0 gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 +=(-q1 * gx - q2 * gy - q3 * gz); - q1 += (q0 * gx + q2 * gz - q3 * gy); - q2 += (q0 * gy - q1 * gz + q3 * gx); - q3 += (q0 * gz + q1 * gy - q2 * gx); +#endif + + // Time derivative of quaternion. q_dot = 0.5*q\otimes omega. + //! q_k = q_{k-1} + dt*\dot{q} + //! \dot{q} = 0.5*q \otimes P(\omega) + dq0 = 0.5f*(-q1 * gx - q2 * gy - q3 * gz); + dq1 = 0.5f*(q0 * gx + q2 * gz - q3 * gy); + dq2 = 0.5f*(q0 * gy - q1 * gz + q3 * gx); + dq3 = 0.5f*(q0 * gz + q1 * gy - q2 * gx); + + q0 += dt*dq0; + q1 += dt*dq1; + q2 += dt*dq2; + q3 += dt*dq3; // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -528,8 +540,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds struct sensor_combined_s raw; memset(&raw, 0, sizeof(raw)); + + //! Initialize attitude vehicle uORB message. struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); + struct vehicle_status_s state; memset(&state, 0, sizeof(state)); @@ -711,7 +726,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds // NOTE : Accelerometer is reversed. // Because proper mount of PX4 will give you a reversed accelerometer readings. - MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + NonlinearSO3AHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); // Convert q->R. Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11 @@ -752,14 +767,27 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.pitch = euler[1] - so3_comp_params.pitch_off; att.yaw = euler[2] - so3_comp_params.yaw_off; - /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ + //! Euler angle rate. But it needs to be investigated again. + /* + att.rollspeed = 2.0f*(-q1*dq0 + q0*dq1 - q3*dq2 + q2*dq3); + att.pitchspeed = 2.0f*(-q2*dq0 + q3*dq1 + q0*dq2 - q1*dq3); + att.yawspeed = 2.0f*(-q3*dq0 -q2*dq1 + q1*dq2 + q0*dq3); + */ att.rollspeed = gyro[0]; att.pitchspeed = gyro[1]; att.yawspeed = gyro[2]; + att.rollacc = 0; att.pitchacc = 0; att.yawacc = 0; + //! Quaternion + att.q[0] = q0; + att.q[1] = q1; + att.q[2] = q2; + att.q[3] = q3; + att.q_valid = true; + /* TODO: Bias estimation required */ memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets)); diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 1d5e0670a0..f962515dfb 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -19,8 +19,15 @@ #include "attitude_estimator_so3_comp_params.h" /* This is filter gain for nonlinear SO3 complementary filter */ -PARAM_DEFINE_FLOAT(SO3_COMP_KP, 0.5f); -PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); +/* NOTE : How to tune the gain? First of all, stick with this default gain. And let the quad in stable place. + Log the steady state reponse of filter. If it is too slow, increase SO3_COMP_KP. + If you are flying from ground to high altitude in short amount of time, please increase SO3_COMP_KI which + will compensate gyro bias which depends on temperature and vibration of your vehicle */ +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); //! This parameter will give you about 15 seconds convergence time. + //! You can set this gain higher if you want more fast response. + //! But note that higher gain will give you also higher overshoot. +PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.05f); //! This gain will incorporate slow time-varying bias (e.g., temperature change) + //! This gain is depend on your vehicle status. /* offsets in roll, pitch and yaw of sensor plane and body */ PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); From 382c9a69e44a6fa5dfa5abec12257ea621018148 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 17:13:10 +0200 Subject: [PATCH 70/89] Removed big RAM consumer (inactive filter) --- makefiles/config_px4fmu_default.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 230a527fec..d50eb1e500 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -63,7 +63,7 @@ MODULES += modules/gpio_led # MODULES += modules/attitude_estimator_ekf MODULES += modules/attitude_estimator_so3_comp -MODULES += modules/position_estimator_mc +#MODULES += modules/position_estimator_mc MODULES += modules/position_estimator MODULES += modules/att_pos_estimator_ekf From b09fc1468c8db65ea99dd94f59f5c075dfce5c7e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 17:25:47 +0200 Subject: [PATCH 71/89] Hotfix: Fix typos in tutorial code --- src/examples/px4_daemon_app/px4_daemon_app.c | 53 +++++++++++--------- 1 file changed, 28 insertions(+), 25 deletions(-) diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index a5d847777e..26f31b9e6c 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Example User + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,27 +32,32 @@ ****************************************************************************/ /** - * @file px4_deamon_app.c - * Deamon application example for PX4 autopilot + * @file px4_daemon_app.c + * daemon application example for PX4 autopilot + * + * @author Example User */ #include +#include #include #include -static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +#include + +static bool thread_should_exit = false; /**< daemon exit flag */ +static bool thread_running = false; /**< daemon status flag */ +static int daemon_task; /**< Handle of daemon task / thread */ /** - * Deamon management function. + * daemon management function. */ -__EXPORT int px4_deamon_app_main(int argc, char *argv[]); +__EXPORT int px4_daemon_app_main(int argc, char *argv[]); /** - * Mainloop of deamon. + * Mainloop of daemon. */ -int px4_deamon_thread_main(int argc, char *argv[]); +int px4_daemon_thread_main(int argc, char *argv[]); /** * Print the correct usage. @@ -64,20 +68,19 @@ static void usage(const char *reason) { if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: deamon {start|stop|status} [-p ]\n\n"); - exit(1); + warnx("%s\n", reason); + errx(1, "usage: daemon {start|stop|status} [-p ]\n\n"); } /** - * The deamon app only briefly exists to start + * The daemon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. * * The actual stack size should be set in the call * to task_create(). */ -int px4_deamon_app_main(int argc, char *argv[]) +int px4_daemon_app_main(int argc, char *argv[]) { if (argc < 1) usage("missing command"); @@ -85,17 +88,17 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("deamon already running\n"); + warnx("daemon already running\n"); /* this is not an error */ exit(0); } thread_should_exit = false; - deamon_task = task_spawn("deamon", + daemon_task = task_spawn("daemon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, - px4_deamon_thread_main, + px4_daemon_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } @@ -107,9 +110,9 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tdeamon app is running\n"); + printf("\tdaemon app is running\n"); } else { - printf("\tdeamon app not started\n"); + printf("\tdaemon app not started\n"); } exit(0); } @@ -118,18 +121,18 @@ int px4_deamon_app_main(int argc, char *argv[]) exit(1); } -int px4_deamon_thread_main(int argc, char *argv[]) { +int px4_daemon_thread_main(int argc, char *argv[]) { - printf("[deamon] starting\n"); + printf("[daemon] starting\n"); thread_running = true; while (!thread_should_exit) { - printf("Hello Deamon!\n"); + printf("Hello daemon!\n"); sleep(10); } - printf("[deamon] exiting.\n"); + printf("[daemon] exiting.\n"); thread_running = false; From fa1b057bb158ab62babef625c57956b2b63707e0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 17:27:01 +0200 Subject: [PATCH 72/89] Minor cleanup --- src/examples/px4_daemon_app/px4_daemon_app.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index 26f31b9e6c..4dd5165c8c 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -110,9 +110,9 @@ int px4_daemon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tdaemon app is running\n"); + warnx("\trunning\n"); } else { - printf("\tdaemon app not started\n"); + warnx("\tnot started\n"); } exit(0); } @@ -123,16 +123,16 @@ int px4_daemon_app_main(int argc, char *argv[]) int px4_daemon_thread_main(int argc, char *argv[]) { - printf("[daemon] starting\n"); + warnx("[daemon] starting\n"); thread_running = true; while (!thread_should_exit) { - printf("Hello daemon!\n"); + warnx("Hello daemon!\n"); sleep(10); } - printf("[daemon] exiting.\n"); + warnx("[daemon] exiting.\n"); thread_running = false; From 026cad832ad4717b762041a78261f7d6faeef894 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 18:53:33 +0200 Subject: [PATCH 73/89] Hotfix: Added missing header --- src/examples/px4_daemon_app/px4_daemon_app.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index 4dd5165c8c..c568aaadcf 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -43,6 +43,7 @@ #include #include +#include #include static bool thread_should_exit = false; /**< daemon exit flag */ From 2aa16dc44764485639921eb4adbbca429c3a4773 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 19:12:10 +0200 Subject: [PATCH 74/89] Hotfix: Disable instrumentation on IO --- makefiles/toolchain_gnu-arm-eabi.mk | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index c75a08bd16..99c2776fdf 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -70,6 +70,14 @@ ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \ -march=armv7-m \ -mfloat-abi=soft +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions \ + -ffixed-r10 + +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions \ + -ffixed-r10 + +ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = + # Pick the right set of flags for the architecture. # ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH)) @@ -91,8 +99,8 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ # enable precise stack overflow tracking # note - requires corresponding support in NuttX -INSTRUMENTATIONDEFINES = -finstrument-functions \ - -ffixed-r10 +INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) + # Language-specific flags # ARCHCFLAGS = -std=gnu99 From 4052652a28232edcdcb8089dcb05a8dc426343e4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Jun 2013 23:19:16 +0400 Subject: [PATCH 75/89] sdlog2: ATTC - vehicle attitude control logging added --- src/modules/sdlog2/sdlog2.c | 8 +++++++- src/modules/sdlog2/sdlog2_messages.h | 10 ++++++++++ 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index b5821098ff..290577790d 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -652,6 +652,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_LPOS_s log_LPOS; struct log_LPSP_s log_LPSP; struct log_GPS_s log_GPS; + struct log_ATTC_s log_ATTC; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -930,7 +931,12 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- ACTUATOR CONTROL --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls); - // TODO not implemented yet + log_msg.msg_type = LOG_ATTC_MSG; + log_msg.body.log_ATTC.roll = buf.act_controls.control[0]; + log_msg.body.log_ATTC.pitch = buf.act_controls.control[1]; + log_msg.body.log_ATTC.yaw = buf.act_controls.control[2]; + log_msg.body.log_ATTC.thrust = buf.act_controls.control[3]; + LOGBUFFER_WRITE_AND_COUNT(ATTC); } /* --- ACTUATOR CONTROL EFFECTIVE --- */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 316459b1e9..44c6b9cbab 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -132,6 +132,15 @@ struct log_GPS_s { float vel_d; float cog; }; + +/* --- ATTC - ATTITUDE CONTROLS --- */ +#define LOG_ATTC_MSG 9 +struct log_ATTC_s { + float roll; + float pitch; + float yaw; + float thrust; +}; #pragma pack(pop) /* construct list of all message formats */ @@ -145,6 +154,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), + LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From b3c5bd5d3a3cc4b480c40b524484aca2b9a66422 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 22:14:11 +0200 Subject: [PATCH 76/89] Saved a few string bytes, cleaned up task names and output --- .../att_pos_estimator_ekf/kalman_main.cpp | 15 ++++++++------- .../fixedwing_backside_main.cpp | 17 +++++++++-------- 2 files changed, 17 insertions(+), 15 deletions(-) diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp index aebe3d1feb..10592ec7c7 100644 --- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp +++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include #include "KalmanNav.hpp" @@ -73,7 +74,7 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: kalman_demo {start|stop|status} [-p ]\n\n"); + warnx("usage: att_pos_estimator_ekf {start|stop|status} [-p ]"); exit(1); } @@ -94,13 +95,13 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("kalman_demo already running\n"); + warnx("already running"); /* this is not an error */ exit(0); } thread_should_exit = false; - deamon_task = task_spawn("kalman_demo", + deamon_task = task_spawn("att_pos_estimator_ekf", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4096, @@ -116,10 +117,10 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tkalman_demo app is running\n"); + warnx("is running\n"); } else { - printf("\tkalman_demo app not started\n"); + warnx("not started\n"); } exit(0); @@ -132,7 +133,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) int kalman_demo_thread_main(int argc, char *argv[]) { - printf("[kalman_demo] starting\n"); + warnx("starting\n"); using namespace math; @@ -144,7 +145,7 @@ int kalman_demo_thread_main(int argc, char *argv[]) nav.update(); } - printf("[kalman_demo] exiting.\n"); + printf("exiting.\n"); thread_running = false; diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp index e21990c929..c3d57a85ae 100644 --- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp +++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp @@ -47,6 +47,7 @@ #include #include #include +#include #include #include @@ -80,7 +81,7 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: control_demo {start|stop|status} [-p ]\n\n"); + fprintf(stderr, "usage: fixedwing_backside {start|stop|status} [-p ]\n\n"); exit(1); } @@ -101,13 +102,13 @@ int fixedwing_backside_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("control_demo already running\n"); + warnx("already running"); /* this is not an error */ exit(0); } thread_should_exit = false; - deamon_task = task_spawn("control_demo", + deamon_task = task_spawn("fixedwing_backside", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 5120, @@ -128,10 +129,10 @@ int fixedwing_backside_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tcontrol_demo app is running\n"); + warnx("is running"); } else { - printf("\tcontrol_demo app not started\n"); + warnx("not started"); } exit(0); @@ -144,7 +145,7 @@ int fixedwing_backside_main(int argc, char *argv[]) int control_demo_thread_main(int argc, char *argv[]) { - printf("[control_Demo] starting\n"); + warnx("starting"); using namespace control; @@ -156,7 +157,7 @@ int control_demo_thread_main(int argc, char *argv[]) autopilot.update(); } - printf("[control_demo] exiting.\n"); + warnx("exiting."); thread_running = false; @@ -165,6 +166,6 @@ int control_demo_thread_main(int argc, char *argv[]) void test() { - printf("beginning control lib test\n"); + warnx("beginning control lib test"); control::basicBlocksTest(); } From 4302f7640216b2bef88d270a268dbea2f712119e Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 6 Jun 2013 22:49:49 -0700 Subject: [PATCH 77/89] Hotfix: fix building firmware parallel --- makefiles/firmware.mk | 12 ++++++------ makefiles/nuttx.mk | 6 +++++- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 6b09e6ec32..f1c1b496a0 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -176,6 +176,12 @@ GLOBAL_DEPS += $(MAKEFILE_LIST) # EXTRA_CLEANS = +################################################################################ +# NuttX libraries and paths +################################################################################ + +include $(PX4_MK_DIR)/nuttx.mk + ################################################################################ # Modules ################################################################################ @@ -296,12 +302,6 @@ $(LIBRARY_CLEANS): LIBRARY_MK=$(mkfile) \ clean -################################################################################ -# NuttX libraries and paths -################################################################################ - -include $(PX4_MK_DIR)/nuttx.mk - ################################################################################ # ROMFS generation ################################################################################ diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk index 346735a02a..d283096b25 100644 --- a/makefiles/nuttx.mk +++ b/makefiles/nuttx.mk @@ -69,10 +69,14 @@ INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \ LIB_DIRS += $(NUTTX_EXPORT_DIR)libs LIBS += -lapps -lnuttx -LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \ +NUTTX_LIBS = $(NUTTX_EXPORT_DIR)libs/libapps.a \ $(NUTTX_EXPORT_DIR)libs/libnuttx.a +LINK_DEPS += $(NUTTX_LIBS) $(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE) @$(ECHO) %% Unpacking $(NUTTX_ARCHIVE) $(Q) $(UNZIP_CMD) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE) $(Q) $(TOUCH) $@ + + $(LDSCRIPT): $(NUTTX_CONFIG_HEADER) + $(NUTTX_LIBS): $(NUTTX_CONFIG_HEADER) From 6c7c130de72b3323211c1ac2e08c8ccf1630c865 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 10:34:55 +0200 Subject: [PATCH 78/89] Hotfix: Make IOs mixer loading pedantic to make sure the full mixer loads --- src/modules/px4iofirmware/mixer.cpp | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 0b8ed6dc59..a2193b526b 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -294,8 +294,7 @@ mixer_handle_text(const void *buffer, size_t length) case F2I_MIXER_ACTION_APPEND: isr_debug(2, "append %d", length); - /* check for overflow - this is really fatal */ - /* XXX could add just what will fit & try to parse, then repeat... */ + /* check for overflow - this would be really fatal */ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) { r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK; return; @@ -314,8 +313,13 @@ mixer_handle_text(const void *buffer, size_t length) /* if anything was parsed */ if (resid != mixer_text_length) { - /* ideally, this should test resid == 0 ? */ - r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK; + /* only set mixer ok if no residual is left over */ + if (resid == 0) { + r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK; + } else { + /* not yet reached the end of the mixer, set as not ok */ + r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK; + } isr_debug(2, "used %u", mixer_text_length - resid); @@ -338,11 +342,13 @@ mixer_set_failsafe() { /* * Check if a custom failsafe value has been written, - * else use the opportunity to set decent defaults. + * or if the mixer is not ok and bail out. */ - if (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) + if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) || + !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) return; + /* set failsafe defaults to the values for all inputs = 0 */ float outputs[IO_SERVO_COUNT]; unsigned mixed; From 11544d27b7629078b6a7a2247f159b535816e019 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 10:35:37 +0200 Subject: [PATCH 79/89] Hotfix: Enlarge the buffer size for mixers, ensure that reasonable setups with 16 outputs can work --- src/systemcmds/mixer/mixer.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/mixer/mixer.c b/src/systemcmds/mixer/mixer.c index 55c4f08362..e642ed0676 100644 --- a/src/systemcmds/mixer/mixer.c +++ b/src/systemcmds/mixer/mixer.c @@ -88,8 +88,8 @@ load(const char *devname, const char *fname) { int dev; FILE *fp; - char line[80]; - char buf[512]; + char line[120]; + char buf[2048]; /* open the device */ if ((dev = open(devname, 0)) < 0) From 4e3f4b57e3e603aaea665758ea0240c48ea9e54f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 10:36:56 +0200 Subject: [PATCH 80/89] Hotfix: Allow the IO mixer loading to load larger mixers, fix up the px4io test command to allow a clean exit --- src/drivers/px4io/px4io.cpp | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 0934e614b3..19163cebe3 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1302,7 +1302,7 @@ PX4IO::print_status() io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT), io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT), io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE)); - printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n", + printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n", (double)_battery_amp_per_volt, (double)_battery_amp_bias, (double)_battery_mamphour_total); @@ -1496,7 +1496,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) case MIXERIOCLOADBUF: { const char *buf = (const char *)arg; - ret = mixer_send(buf, strnlen(buf, 1024)); + ret = mixer_send(buf, strnlen(buf, 2048)); break; } @@ -1637,6 +1637,13 @@ test(void) if (ioctl(fd, PWM_SERVO_ARM, 0)) err(1, "failed to arm servos"); + /* Open console directly to grab CTRL-C signal */ + int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY); + if (!console) + err(1, "failed opening console"); + + warnx("Press CTRL-C or 'c' to abort."); + for (;;) { /* sweep all servos between 1000..2000 */ @@ -1671,6 +1678,16 @@ test(void) if (value != servos[i]) errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]); } + + /* Check if user wants to quit */ + char c; + if (read(console, &c, 1) == 1) { + if (c == 0x03 || c == 0x63) { + warnx("User abort\n"); + close(console); + exit(0); + } + } } } From 5b5d20bb638c884f943612da43a5ce30c1742eb8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 10:37:31 +0200 Subject: [PATCH 81/89] Hotfix: Add an IO pass mixer with 8 outputs --- ROMFS/px4fmu_common/mixers/IO_pass.mix | 38 ++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) create mode 100644 ROMFS/px4fmu_common/mixers/IO_pass.mix diff --git a/ROMFS/px4fmu_common/mixers/IO_pass.mix b/ROMFS/px4fmu_common/mixers/IO_pass.mix new file mode 100644 index 0000000000..39f875ddb9 --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/IO_pass.mix @@ -0,0 +1,38 @@ +Passthrough mixer for PX4IO +============================ + +This file defines passthrough mixers suitable for testing. + +Channel group 0, channels 0-7 are passed directly through to the outputs. + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 0 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 2 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 3 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 4 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 5 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 6 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 7 10000 10000 0 -10000 10000 From 5c74809dac57f58f92ad92433496731481703982 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 10:38:09 +0200 Subject: [PATCH 82/89] Config change: Set USB console as default. --- nuttx/configs/px4fmu/nsh/defconfig | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 02e2243020..0662f7fbe3 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_SERIAL_CONSOLE=n CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y +CONFIG_DEV_CONSOLE=n CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -717,7 +717,7 @@ CONFIG_ARCH_BZERO=n # zero for all dynamic allocations. # CONFIG_MAX_TASKS=32 -CONFIG_MAX_TASK_ARGS=8 +CONFIG_MAX_TASK_ARGS=10 CONFIG_NPTHREAD_KEYS=4 CONFIG_NFILE_DESCRIPTORS=32 CONFIG_NFILE_STREAMS=25 @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=n +CONFIG_CDCACM_CONSOLE=y #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE From 5bad18691649b4b50d46c11384c3aa5051b6519e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 7 Jun 2013 13:36:15 +0400 Subject: [PATCH 83/89] sdlog2: STAT (vehicle state) log message added, minor optimizations --- src/modules/sdlog2/sdlog2.c | 34 +++++++++++++++++++++++----- src/modules/sdlog2/sdlog2_messages.h | 15 ++++++++++++ 2 files changed, 43 insertions(+), 6 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 290577790d..32bd422bc7 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -597,10 +597,12 @@ int sdlog2_thread_main(int argc, char *argv[]) /* file descriptors to wait for */ struct pollfd fds[fdsc]; + struct vehicle_status_s buf_status; + memset(&buf_status, 0, sizeof(buf_status)); + /* warning! using union here to save memory, elements should be used separately! */ union { struct vehicle_command_s cmd; - struct vehicle_status_s status; struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; @@ -653,6 +655,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_LPSP_s log_LPSP; struct log_GPS_s log_GPS; struct log_ATTC_s log_ATTC; + struct log_STAT_s log_STAT; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -803,22 +806,25 @@ int sdlog2_thread_main(int argc, char *argv[]) * logging_enabled can be changed while checking vehicle_command and vehicle_status */ bool check_data = logging_enabled; int ifds = 0; + int handled_topics = 0; - /* --- VEHICLE COMMAND --- */ + /* --- VEHICLE COMMAND - LOG MANAGEMENT --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); handle_command(&buf.cmd); + handled_topics++; } - /* --- VEHICLE STATUS --- */ + /* --- VEHICLE STATUS - LOG MANAGEMENT --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf.status); + orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status); if (log_when_armed) { - handle_status(&buf.status); + handle_status(&buf_status); } + handled_topics++; } - if (!logging_enabled || !check_data) { + if (!logging_enabled || !check_data || handled_topics >= poll_ret) { continue; } @@ -829,6 +835,22 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_TIME.t = hrt_absolute_time(); LOGBUFFER_WRITE_AND_COUNT(TIME); + /* --- VEHICLE STATUS --- */ + if (fds[ifds++].revents & POLLIN) { + // Don't orb_copy, it's already done few lines above + log_msg.msg_type = LOG_STAT_MSG; + log_msg.body.log_STAT.state = (unsigned char) buf_status.state_machine; + log_msg.body.log_STAT.flight_mode = (unsigned char) buf_status.flight_mode; + log_msg.body.log_STAT.manual_control_mode = (unsigned char) buf_status.manual_control_mode; + log_msg.body.log_STAT.manual_sas_mode = (unsigned char) buf_status.manual_sas_mode; + log_msg.body.log_STAT.armed = (unsigned char) buf_status.flag_system_armed; + log_msg.body.log_STAT.battery_voltage = buf_status.voltage_battery; + log_msg.body.log_STAT.battery_current = buf_status.current_battery; + log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining; + log_msg.body.log_STAT.battery_warning = (unsigned char) buf_status.battery_warning; + LOGBUFFER_WRITE_AND_COUNT(STAT); + } + /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 44c6b9cbab..2b6b865215 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -141,6 +141,20 @@ struct log_ATTC_s { float yaw; float thrust; }; + +/* --- STAT - VEHICLE STATE --- */ +#define LOG_STAT_MSG 10 +struct log_STAT_s { + unsigned char state; + unsigned char flight_mode; + unsigned char manual_control_mode; + unsigned char manual_sas_mode; + unsigned char armed; + float battery_voltage; + float battery_current; + float battery_remaining; + unsigned char battery_warning; +}; #pragma pack(pop) /* construct list of all message formats */ @@ -155,6 +169,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"), + LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From aa641b5c348b5236f5d7f882daa6a7b2ff98fd83 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 18:00:37 +0200 Subject: [PATCH 84/89] Hotfix: Renamed max NSH argument variable to correct define --- nuttx/configs/px4fmu/nsh/defconfig | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) mode change 100755 => 100644 nuttx/configs/px4fmu/nsh/defconfig diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig old mode 100755 new mode 100644 index 0662f7fbe3..248e508c20 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -955,7 +955,7 @@ CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6" # CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer # CONFIG_NSH_STRERROR - Use strerror(errno) # CONFIG_NSH_LINELEN - Maximum length of one command line -# CONFIG_NSH_MAX_ARGUMENTS - Maximum number of arguments for command line +# CONFIG_NSH_MAXARGUMENTS - Maximum number of arguments for command line # CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi # CONFIG_NSH_DISABLESCRIPT - Disable scripting support # CONFIG_NSH_DISABLEBG - Disable background commands @@ -988,7 +988,7 @@ CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_FILEIOSIZE=512 CONFIG_NSH_STRERROR=y CONFIG_NSH_LINELEN=128 -CONFIG_NSH_MAX_ARGUMENTS=12 +CONFIG_NSH_MAXARGUMENTS=12 CONFIG_NSH_NESTDEPTH=8 CONFIG_NSH_DISABLESCRIPT=n CONFIG_NSH_DISABLEBG=n From d39999425d92997ca9db77305d5c87268c601d49 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 7 Jun 2013 21:32:58 +0400 Subject: [PATCH 85/89] sdlog2 fixes --- src/modules/sdlog2/sdlog2.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 32bd422bc7..6fc430fc93 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -484,7 +484,7 @@ void sdlog2_stop_log() warnx("stop logging."); mavlink_log_info(mavlink_fd, "[sdlog2] stop logging"); - logging_enabled = true; + logging_enabled = false; logwriter_should_exit = true; /* wake up write thread one last time */ @@ -828,6 +828,8 @@ int sdlog2_thread_main(int argc, char *argv[]) continue; } + ifds = 1; // Begin from fds[1] again + pthread_mutex_lock(&logbuffer_mutex); /* write time stamp message */ From 59b26eca48212f13a467724f9445169b78d6c70a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 7 Jun 2013 22:02:40 +0400 Subject: [PATCH 86/89] sdlog2 -b option (log buffer size) added, minor cleanup --- src/modules/sdlog2/logbuffer.c | 3 +- src/modules/sdlog2/logbuffer.h | 4 +-- src/modules/sdlog2/sdlog2.c | 50 ++++++++++++++++++++++++---------- 3 files changed, 40 insertions(+), 17 deletions(-) diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index 4205bcf20d..8aaafaf316 100644 --- a/src/modules/sdlog2/logbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -45,12 +45,13 @@ #include "logbuffer.h" -void logbuffer_init(struct logbuffer_s *lb, int size) +int logbuffer_init(struct logbuffer_s *lb, int size) { lb->size = size; lb->write_ptr = 0; lb->read_ptr = 0; lb->data = malloc(lb->size); + return (lb->data == 0) ? ERROR : OK; } int logbuffer_count(struct logbuffer_s *lb) diff --git a/src/modules/sdlog2/logbuffer.h b/src/modules/sdlog2/logbuffer.h index e9635e5e73..31521f722e 100644 --- a/src/modules/sdlog2/logbuffer.h +++ b/src/modules/sdlog2/logbuffer.h @@ -46,14 +46,14 @@ #include struct logbuffer_s { - // all pointers are in bytes + // pointers and size are in bytes int write_ptr; int read_ptr; int size; char *data; }; -void logbuffer_init(struct logbuffer_s *lb, int size); +int logbuffer_init(struct logbuffer_s *lb, int size); int logbuffer_count(struct logbuffer_s *lb); diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 6fc430fc93..4ad339aede 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -94,9 +94,9 @@ } #define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \ - fds[fdsc_count].fd = subs.##_var##_sub; \ - fds[fdsc_count].events = POLLIN; \ - fdsc_count++; + fds[fdsc_count].fd = subs.##_var##_sub; \ + fds[fdsc_count].events = POLLIN; \ + fdsc_count++; //#define SDLOG2_DEBUG @@ -107,7 +107,7 @@ static int deamon_task; /**< Handle of deamon task / thread */ static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */ static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */ -static const int LOG_BUFFER_SIZE = 8192; +static const int LOG_BUFFER_SIZE_DEFAULT = 8192; static const int MAX_WRITE_CHUNK = 512; static const int MIN_BYTES_TO_WRITE = 512; @@ -207,8 +207,9 @@ sdlog2_usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - errx(1, "usage: sdlog2 {start|stop|status} [-r ] -e -a\n" + errx(1, "usage: sdlog2 {start|stop|status} [-r ] [-b ] -e -a\n" "\t-r\tLog rate in Hz, 0 means unlimited rate\n" + "\t-r\tLog buffer size in KBytes, default is 8\n" "\t-e\tEnable logging by default (if not, can be started by command)\n" "\t-a\tLog only when armed (can be still overriden by command)\n"); } @@ -529,18 +530,18 @@ int sdlog2_thread_main(int argc, char *argv[]) warnx("failed to open MAVLink log stream, start mavlink app first."); } - /* log every n'th value (skip three per default) */ - int skip_value = 3; + /* log buffer size */ + int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT; /* work around some stupidity in task_create's argv handling */ argc -= 2; argv += 2; int ch; - while ((ch = getopt(argc, argv, "r:ea")) != EOF) { + while ((ch = getopt(argc, argv, "r:b:ea")) != EOF) { switch (ch) { case 'r': { - unsigned r = strtoul(optarg, NULL, 10); + unsigned long r = strtoul(optarg, NULL, 10); if (r == 0) { sleep_delay = 0; @@ -551,6 +552,20 @@ int sdlog2_thread_main(int argc, char *argv[]) } break; + case 'b': { + unsigned long s = strtoul(optarg, NULL, 10); + + if (s < 1) { + s = 1; + + } else if (s > 640) { + s = 640; + } + + log_buffer_size = 1024 * s; + } + break; + case 'e': log_on_start = true; break; @@ -572,7 +587,7 @@ int sdlog2_thread_main(int argc, char *argv[]) default: sdlog2_usage("unrecognized flag"); - errx(1, "exiting"); + errx(1, "exiting."); } } @@ -580,12 +595,20 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "logging mount point %s not present, exiting.", mountpoint); } - if (create_logfolder()) + if (create_logfolder()) { errx(1, "unable to create logging folder, exiting."); + } /* only print logging path, important to find log file later */ warnx("logging to directory: %s", folder_path); + /* initialize log buffer with specified size */ + warnx("log buffer size: %i bytes.", log_buffer_size); + + if (OK != logbuffer_init(&lb, log_buffer_size)) { + errx(1, "can't allocate log buffer, exiting."); + } + /* file descriptors to wait for */ struct pollfd fds_control[2]; @@ -770,9 +793,6 @@ int sdlog2_thread_main(int argc, char *argv[]) thread_running = true; - /* initialize log buffer with specified size */ - logbuffer_init(&lb, LOG_BUFFER_SIZE); - /* initialize thread synchronization */ pthread_mutex_init(&logbuffer_mutex, NULL); pthread_cond_init(&logbuffer_cond, NULL); @@ -818,9 +838,11 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- VEHICLE STATUS - LOG MANAGEMENT --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status); + if (log_when_armed) { handle_status(&buf_status); } + handled_topics++; } From 7b98f0a56749809ce0150bad6983ac9956250abd Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 7 Jun 2013 22:12:21 +0400 Subject: [PATCH 87/89] sdlog2 minor fix --- src/modules/sdlog2/sdlog2.c | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 4ad339aede..b6ab8c2edb 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -557,9 +557,6 @@ int sdlog2_thread_main(int argc, char *argv[]) if (s < 1) { s = 1; - - } else if (s > 640) { - s = 640; } log_buffer_size = 1024 * s; From 66879e6ff64b23e417b4101243922cefd34eef7d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Jun 2013 21:16:31 +0200 Subject: [PATCH 88/89] Hotfix: Make maxoptimization configurable from the shell via MAXOPTIMIZATION=-O0 V=1 make archives --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- nuttx/arch/arm/src/armv7-m/Toolchain.defs | 2 +- nuttx/configs/px4fmu/common/Make.defs | 2 +- nuttx/configs/px4io/common/Make.defs | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 99c2776fdf..3f4d3371ac 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -50,7 +50,7 @@ OBJDUMP = $(CROSSDEV)objdump # XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION ?= -O3 # Base CPU flags for each of the supported architectures. # diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs index 4de5b49f4a..1ba764593d 100644 --- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs +++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs @@ -243,7 +243,7 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI) CROSSDEV ?= arm-none-eabi- ARCROSSDEV ?= arm-none-eabi- - MAXOPTIMIZATION = -O3 + MAXOPTIMIZATION ?= -O3 ifeq ($(CONFIG_ARCH_CORTEXM4),y) ifeq ($(CONFIG_ARCH_FPU),y) ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs index 756286ccb5..22accee563 100644 --- a/nuttx/configs/px4fmu/common/Make.defs +++ b/nuttx/configs/px4fmu/common/Make.defs @@ -58,7 +58,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION ?= -O3 ARCHCPUFLAGS = -mcpu=cortex-m4 \ -mthumb \ -march=armv7e-m \ diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs index 7f782b5b22..d2490d84ea 100644 --- a/nuttx/configs/px4io/common/Make.defs +++ b/nuttx/configs/px4io/common/Make.defs @@ -58,7 +58,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION ?= -O3 ARCHCPUFLAGS = -mcpu=cortex-m3 \ -mthumb \ -march=armv7-m From 079cb2cd652ec3dd2be011e30bbe459437e80d44 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 8 Jun 2013 18:15:55 +0400 Subject: [PATCH 89/89] sdlog2: RC (RC controls) and OUT0 (actuator 0 output) messages added, print statistics to mavlink console --- src/modules/sdlog2/sdlog2.c | 38 +++++++++++++++++----------- src/modules/sdlog2/sdlog2_messages.h | 16 +++++++++++- 2 files changed, 38 insertions(+), 16 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index b6ab8c2edb..a14bd6f80e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -77,6 +77,7 @@ #include #include #include +#include #include @@ -209,7 +210,7 @@ sdlog2_usage(const char *reason) errx(1, "usage: sdlog2 {start|stop|status} [-r ] [-b ] -e -a\n" "\t-r\tLog rate in Hz, 0 means unlimited rate\n" - "\t-r\tLog buffer size in KBytes, default is 8\n" + "\t-b\tLog buffer size in KiB, default is 8\n" "\t-e\tEnable logging by default (if not, can be started by command)\n" "\t-a\tLog only when armed (can be still overriden by command)\n"); } @@ -635,7 +636,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct vehicle_gps_position_s gps_pos; struct vehicle_vicon_position_s vicon_pos; struct optical_flow_s flow; - struct battery_status_s batt; + struct rc_channels_s rc; struct differential_pressure_s diff_pres; struct airspeed_s airspeed; } buf; @@ -656,9 +657,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int gps_pos_sub; int vicon_pos_sub; int flow_sub; - int batt_sub; - int diff_pres_sub; - int airspeed_sub; + int rc_sub; } subs; /* log message buffer: header + body */ @@ -676,6 +675,8 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_GPS_s log_GPS; struct log_ATTC_s log_ATTC; struct log_STAT_s log_STAT; + struct log_RC_s log_RC; + struct log_OUT0_s log_OUT0; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -720,7 +721,7 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- ACTUATOR OUTPUTS --- */ - subs.act_outputs_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); + subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS); fds[fdsc_count].fd = subs.act_outputs_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; @@ -767,9 +768,9 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- BATTERY STATUS --- */ - subs.batt_sub = orb_subscribe(ORB_ID(battery_status)); - fds[fdsc_count].fd = subs.batt_sub; + /* --- RC CHANNELS --- */ + subs.rc_sub = orb_subscribe(ORB_ID(rc_channels)); + fds[fdsc_count].fd = subs.rc_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; @@ -968,7 +969,9 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- ACTUATOR OUTPUTS --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs); - // TODO not implemented yet + log_msg.msg_type = LOG_OUT0_MSG; + memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output)); + LOGBUFFER_WRITE_AND_COUNT(OUT0); } /* --- ACTUATOR CONTROL --- */ @@ -1034,10 +1037,13 @@ int sdlog2_thread_main(int argc, char *argv[]) // TODO not implemented yet } - /* --- BATTERY STATUS --- */ + /* --- RC CHANNELS --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt); - // TODO not implemented yet + orb_copy(ORB_ID(rc_channels), subs.rc_sub, &buf.rc); + log_msg.msg_type = LOG_RC_MSG; + /* Copy only the first 8 channels of 14 */ + memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel)); + LOGBUFFER_WRITE_AND_COUNT(RC); } /* signal the other thread new data, but not yet unlock */ @@ -1073,10 +1079,12 @@ int sdlog2_thread_main(int argc, char *argv[]) void sdlog2_status() { - float mebibytes = log_bytes_written / 1024.0f / 1024.0f; + float kibibytes = log_bytes_written / 1024.0f; + float mebibytes = kibibytes / 1024.0f; float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; - warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); + warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped); + mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs.", log_msgs_written, log_msgs_skipped); } /** diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 2b6b865215..40763ee1e0 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -133,7 +133,7 @@ struct log_GPS_s { float cog; }; -/* --- ATTC - ATTITUDE CONTROLS --- */ +/* --- ATTC - ATTITUDE CONTROLS (ACTUATOR_0 CONTROLS)--- */ #define LOG_ATTC_MSG 9 struct log_ATTC_s { float roll; @@ -155,6 +155,18 @@ struct log_STAT_s { float battery_remaining; unsigned char battery_warning; }; + +/* --- RC - RC INPUT CHANNELS --- */ +#define LOG_RC_MSG 11 +struct log_RC_s { + float channel[8]; +}; + +/* --- OUT0 - ACTUATOR_0 OUTPUT --- */ +#define LOG_OUT0_MSG 12 +struct log_OUT0_s { + float output[8]; +}; #pragma pack(pop) /* construct list of all message formats */ @@ -170,6 +182,8 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"), LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"), + LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"), + LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);