diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 4572cb9324fa3c..8bf42f38a7c4f1 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -66,8 +66,8 @@ extern const AP_HAL::HAL &hal; VelU */ -static const uint8_t vn_ins_pkt1_header[]{0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06}; -#define VN_INS_PKT1_LENGTH 170 // includes header and CRC +static const uint8_t vn_ins_pkt1_header[] { 0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06 }; +#define VN_INS_PKT1_LENGTH 170 // includes header and CRC struct PACKED VN_INS_packet1 { float uncompMag[3]; @@ -87,8 +87,7 @@ struct PACKED VN_INS_packet1 { }; // check packet size for 4 groups -static_assert(sizeof(VN_INS_packet1) + 2 + 3 * 2 + 2 == VN_INS_PKT1_LENGTH, - "incorrect VN_INS_packet1 length"); +static_assert(sizeof(VN_INS_packet1)+2+3*2+2 == VN_INS_PKT1_LENGTH, "incorrect VN_INS_packet1 length"); /* header for 5Hz GNSS data @@ -114,8 +113,8 @@ static_assert(sizeof(VN_INS_packet1) + 2 + 3 * 2 + 2 == VN_INS_PKT1_LENGTH, NumSats Fix */ -static const uint8_t vn_ins_pkt2_header[]{0x4e, 0x02, 0x00, 0x10, 0x00, 0xb8, 0x20, 0x18, 0x00}; -#define VN_INS_PKT2_LENGTH 92 // includes header and CRC +static const uint8_t vn_ins_pkt2_header[] { 0x4e, 0x02, 0x00, 0x10, 0x00, 0xb8, 0x20, 0x18, 0x00 }; +#define VN_INS_PKT2_LENGTH 92 // includes header and CRC struct PACKED VN_INS_packet2 { uint64_t timeGPS; @@ -130,11 +129,10 @@ struct PACKED VN_INS_packet2 { }; // check packet size for 4 groups -static_assert(sizeof(VN_INS_packet2) + 2 + 4 * 2 + 2 == VN_INS_PKT2_LENGTH, - "incorrect VN_INS_packet2 length"); +static_assert(sizeof(VN_INS_packet2)+2+4*2+2 == VN_INS_PKT2_LENGTH, "incorrect VN_INS_packet2 length"); /* -header for 50Hz IMU data, used in TYPE::VN_AHRS only +header for 50Hz IMU data, used in TYPE::VN_AHRS only assumes the following VN-100 config: $VNWRG,75,3,80,14,073E,0004*66 @@ -154,8 +152,8 @@ header for 50Hz IMU data, used in TYPE::VN_AHRS only 0x0004: Quaternion */ -static const uint8_t vn_ahrs_pkt1_header[]{0x14, 0x3E, 0x07, 0x04, 0x00}; -#define VN_AHRS_PKT1_LENGTH 104 // includes header and CRC +static const uint8_t vn_ahrs_pkt1_header[] { 0x14, 0x3E, 0x07, 0x04, 0x00 }; +#define VN_AHRS_PKT1_LENGTH 104 // includes header and CRC struct PACKED VN_AHRS_packet1 { float uncompMag[3]; @@ -169,15 +167,15 @@ struct PACKED VN_AHRS_packet1 { float quaternion[4]; }; -static_assert(sizeof(VN_AHRS_packet1) + 2 + 2 * 2 + 2 == VN_AHRS_PKT1_LENGTH, - "incorrect VN_AHRS_packet1 length"); +static_assert(sizeof(VN_AHRS_packet1)+2+2*2+2 == VN_AHRS_PKT1_LENGTH, "incorrect VN_AHRS_packet1 length"); // constructor AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, - AP_ExternalAHRS::state_t &_state) - : AP_ExternalAHRS_backend(_frontend, _state) { + AP_ExternalAHRS::state_t &_state) : + AP_ExternalAHRS_backend(_frontend, _state) +{ auto &sm = AP::serialmanager(); - uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); + uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); if (!uart) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS no UART"); return; @@ -185,8 +183,8 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); - bufsize = MAX(MAX(VN_INS_PKT1_LENGTH, VN_INS_PKT2_LENGTH), VN_AHRS_PKT1_LENGTH); - pktbuf = NEW_NOTHROW uint8_t[bufsize]; + bufsize = MAX(MAX(VN_INS_PKT1_LENGTH, VN_INS_PKT2_LENGTH), VN_AHRS_PKT1_LENGTH); + pktbuf = NEW_NOTHROW uint8_t[bufsize]; last_ins_pkt1 = NEW_NOTHROW VN_INS_packet1; last_ins_pkt2 = NEW_NOTHROW VN_INS_packet2; @@ -194,9 +192,7 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, AP_BoardConfig::allocation_error("VectorNav ExternalAHRS"); } - if (!hal.scheduler->thread_create( - FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_VectorNav::update_thread, void), "AHRS", 2048, - AP_HAL::Scheduler::PRIORITY_SPI, 0)) { + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_VectorNav::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { AP_HAL::panic("VectorNav Failed to start ExternalAHRS update thread"); } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS initialised"); @@ -207,7 +203,8 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, returns true if the function should be called again straight away */ #define SYNC_BYTE 0xFA -bool AP_ExternalAHRS_VectorNav::check_uart() { +bool AP_ExternalAHRS_VectorNav::check_uart() +{ if (!setup_complete) { return false; } @@ -219,7 +216,7 @@ bool AP_ExternalAHRS_VectorNav::check_uart() { return false; } if (pktoffset < bufsize) { - ssize_t nread = uart->read(&pktbuf[pktoffset], MIN(n, unsigned(bufsize - pktoffset))); + ssize_t nread = uart->read(&pktbuf[pktoffset], MIN(n, unsigned(bufsize-pktoffset))); if (nread <= 0) { return false; } @@ -235,44 +232,41 @@ bool AP_ExternalAHRS_VectorNav::check_uart() { } if (type == TYPE::VN_INS) { - match_header1 = (0 == memcmp(&pktbuf[1], vn_ins_pkt1_header, - MIN(sizeof(vn_ins_pkt1_header), unsigned(pktoffset - 1)))); - match_header2 = (0 == memcmp(&pktbuf[1], vn_ins_pkt2_header, - MIN(sizeof(vn_ins_pkt2_header), unsigned(pktoffset - 1)))); + match_header1 = (0 == memcmp(&pktbuf[1], vn_ins_pkt1_header, MIN(sizeof(vn_ins_pkt1_header), unsigned(pktoffset-1)))); + match_header2 = (0 == memcmp(&pktbuf[1], vn_ins_pkt2_header, MIN(sizeof(vn_ins_pkt2_header), unsigned(pktoffset-1)))); } else { - match_header3 = (0 == memcmp(&pktbuf[1], vn_ahrs_pkt1_header, - MIN(sizeof(vn_ahrs_pkt1_header), unsigned(pktoffset - 1)))); + match_header3 = (0 == memcmp(&pktbuf[1], vn_ahrs_pkt1_header, MIN(sizeof(vn_ahrs_pkt1_header), unsigned(pktoffset-1)))); } if (!match_header1 && !match_header2 && !match_header3) { goto reset; } if (match_header1 && pktoffset >= VN_INS_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT1_LENGTH - 1, 0); + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT1_LENGTH-1, 0); if (crc == 0) { // got pkt1 - process_ins_packet1(&pktbuf[sizeof(vn_ins_pkt1_header) + 1]); - memmove(&pktbuf[0], &pktbuf[VN_INS_PKT1_LENGTH], pktoffset - VN_INS_PKT1_LENGTH); + process_ins_packet1(&pktbuf[sizeof(vn_ins_pkt1_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_PKT1_LENGTH], pktoffset-VN_INS_PKT1_LENGTH); pktoffset -= VN_INS_PKT1_LENGTH; } else { goto reset; } } else if (match_header2 && pktoffset >= VN_INS_PKT2_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT2_LENGTH - 1, 0); + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT2_LENGTH-1, 0); if (crc == 0) { // got pkt2 - process_ins_packet2(&pktbuf[sizeof(vn_ins_pkt2_header) + 1]); - memmove(&pktbuf[0], &pktbuf[VN_INS_PKT2_LENGTH], pktoffset - VN_INS_PKT2_LENGTH); + process_ins_packet2(&pktbuf[sizeof(vn_ins_pkt2_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_PKT2_LENGTH], pktoffset-VN_INS_PKT2_LENGTH); pktoffset -= VN_INS_PKT2_LENGTH; } else { goto reset; } } else if (match_header3 && pktoffset >= VN_AHRS_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_PKT1_LENGTH - 1, 0); + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_PKT1_LENGTH-1, 0); if (crc == 0) { // got AHRS pkt - process_ahrs_packet(&pktbuf[sizeof(vn_ahrs_pkt1_header) + 1]); - memmove(&pktbuf[0], &pktbuf[VN_AHRS_PKT1_LENGTH], pktoffset - VN_AHRS_PKT1_LENGTH); + process_ahrs_packet(&pktbuf[sizeof(vn_ahrs_pkt1_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_AHRS_PKT1_LENGTH], pktoffset-VN_AHRS_PKT1_LENGTH); pktoffset -= VN_AHRS_PKT1_LENGTH; } else { goto reset; @@ -281,7 +275,7 @@ bool AP_ExternalAHRS_VectorNav::check_uart() { return true; reset: - uint8_t *p = (uint8_t *)memchr(&pktbuf[1], SYNC_BYTE, pktoffset - 1); + uint8_t *p = (uint8_t *)memchr(&pktbuf[1], SYNC_BYTE, pktoffset-1); if (p) { uint8_t newlen = pktoffset - (p - pktbuf); memmove(&pktbuf[0], p, newlen); @@ -292,17 +286,18 @@ bool AP_ExternalAHRS_VectorNav::check_uart() { return true; } -// Send command to read given register number and wait for response +// Send command and wait for response // Only run from thread! This blocks until a response is received #define READ_REQUEST_RETRY_MS 500 -void AP_ExternalAHRS_VectorNav::wait_register_response() { +void AP_ExternalAHRS_VectorNav::send_command_blocking() +{ uint32_t request_sent = 0; while (true) { hal.scheduler->delay(1); const uint32_t now = AP_HAL::millis(); if (now - request_sent > READ_REQUEST_RETRY_MS) { - nmea_printf(uart, "%s", message_to_send); + nmea_printf(uart, "$%s", message_to_send); request_sent = now; } @@ -318,45 +313,47 @@ void AP_ExternalAHRS_VectorNav::wait_register_response() { // add a single character to the buffer and attempt to decode // returns true if a complete sentence was successfully decoded -bool AP_ExternalAHRS_VectorNav::decode(char c) { +bool AP_ExternalAHRS_VectorNav::decode(char c) +{ switch (c) { - case ',': - // end of a term, add to checksum - nmea.checksum ^= c; - FALLTHROUGH; - case '\r': - case '\n': - case '*': { - if (nmea.sentence_done) { - return false; - } - if (nmea.term_is_checksum) { - nmea.sentence_done = true; - uint8_t checksum = 16 * char_to_hex(nmea.term[0]) + char_to_hex(nmea.term[1]); - return ((checksum == nmea.checksum) && nmea.sentence_valid); - } - - // null terminate and decode latest term - nmea.term[nmea.term_offset] = 0; - if (nmea.sentence_valid) { - nmea.sentence_valid = decode_latest_term(); - } - - // move onto next term - nmea.term_number++; - nmea.term_offset = 0; - nmea.term_is_checksum = (c == '*'); + case ',': + // end of a term, add to checksum + nmea.checksum ^= c; + FALLTHROUGH; + case '\r': + case '\n': + case '*': + { + if (nmea.sentence_done) { return false; } + if (nmea.term_is_checksum) { + nmea.sentence_done = true; + uint8_t checksum = 16 * char_to_hex(nmea.term[0]) + char_to_hex(nmea.term[1]); + return ((checksum == nmea.checksum) && nmea.sentence_valid); + } - case '$': // sentence begin - nmea.sentence_valid = true; - nmea.term_number = 0; - nmea.term_offset = 0; - nmea.checksum = 0; - nmea.term_is_checksum = false; - nmea.sentence_done = false; - return false; + // null terminate and decode latest term + nmea.term[nmea.term_offset] = 0; + if (nmea.sentence_valid) { + nmea.sentence_valid = decode_latest_term(); + } + + // move onto next term + nmea.term_number++; + nmea.term_offset = 0; + nmea.term_is_checksum = (c == '*'); + return false; + } + + case '$': // sentence begin + nmea.sentence_valid = true; + nmea.term_number = 0; + nmea.term_offset = 0; + nmea.checksum = 0; + nmea.term_is_checksum = false; + nmea.sentence_done = false; + return false; } // ordinary characters are added to term @@ -372,33 +369,32 @@ bool AP_ExternalAHRS_VectorNav::decode(char c) { // decode the most recently consumed term // returns true if new term is valid -bool AP_ExternalAHRS_VectorNav::decode_latest_term() { +bool AP_ExternalAHRS_VectorNav::decode_latest_term() +{ // Check the first two terms (In most cases header + reg number) that they match the sent // message. If not, the response is invalid. switch (nmea.term_number) { - case 0: { - if (strncmp(nmea.term, message_to_send + 1, nmea.term_offset) != + case 0: + if (strncmp(nmea.term, message_to_send, nmea.term_offset) != 0) { // ignore sync byte in comparison return false; } else if (strncmp(nmea.term, "VNERR", nmea.term_offset) == 0) { - AP_HAL::panic("VectorNav received unexpected VN error"); + AP_HAL::panic("VectorNav received VN error response"); } break; - } - case 1: { - if (strncmp(nmea.term, message_to_send + 7, - nmea.term_offset) != 0) { // Start after "$VNXXX," + case 1: + if (strncmp(nmea.term, message_to_send + 6, + nmea.term_offset) != 0) { // Start after "VNXXX," return false; } break; - } - case 2: { - const bool is_model_number = strncmp(nmea.term, "VN-", 3) == 0; - if (is_model_number) { + case 2: + if (strncmp(nmea.term, "VN-", 3) == 0) { + // This term is the model number strncpy(model_name, nmea.term, sizeof(model_name)); break; } - } + default: break; } @@ -408,22 +404,13 @@ bool AP_ExternalAHRS_VectorNav::decode_latest_term() { void AP_ExternalAHRS_VectorNav::initialize() { // Open port in the thread uart->begin(baudrate, 1024, 512); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav initializing"); - - hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNASY,0\0"); - wait_register_response(); - - // Stop ASCII async outputs for both UARTs. If only active UART is disabled, we get a baudrate - // overflow on the other UART when configuring binary outputs (reg 75 and 76) to both UARTs - hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNWRG,06,1\0"); - wait_register_response(); - hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNWRG,06,2\0"); - wait_register_response(); + hal.util->snprintf(message_to_send, sizeof(message_to_send), "VNWRG,06,0\0"); + send_command_blocking(); // Read Model Number Register, ID 1 - hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNRRG,01\0"); - wait_register_response(); + hal.util->snprintf(message_to_send, sizeof(message_to_send), "VNRRG,01\0"); + send_command_blocking(); // Setup for messages respective model types (on both UARTs) if (strncmp(model_name, "VN-1", 4) == 0) { @@ -432,12 +419,11 @@ void AP_ExternalAHRS_VectorNav::initialize() { // This assumes unit is still configured at its default rate of 800hz hal.util->snprintf(message_to_send, sizeof(message_to_send), - "$VNWRG,75,3,%u,14,073E,0004\0", unsigned(800 / get_rate())); - wait_register_response(); + "VNWRG,75,3,%u,14,073E,0004\0", unsigned(800 / get_rate())); + send_command_blocking(); } else { // Default to setup for sensors other than VN-100 or VN-110 - // This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz - // for others + // This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz for others uint16_t imu_rate = 800; // Default for everything but VN-300 if (strncmp(model_name, "VN-300", 6) == 0) { imu_rate = 400; @@ -446,14 +432,12 @@ void AP_ExternalAHRS_VectorNav::initialize() { has_dual_gnss = true; } hal.util->snprintf(message_to_send, sizeof(message_to_send), - "$VNWRG,75,3,%u,34,072E,0106,0612\0", unsigned(imu_rate / get_rate())); - wait_register_response(); + "VNWRG,75,3,%u,34,072E,0106,0612\0", unsigned(imu_rate / get_rate())); + send_command_blocking(); hal.util->snprintf(message_to_send, sizeof(message_to_send), - "$VNWRG,76,3,%u,4E,0002,0010,20B8,0018\0", unsigned(imu_rate / 5)); - wait_register_response(); + "VNWRG,76,3,%u,4E,0002,0010,20B8,0018\0", unsigned(imu_rate / 5)); + send_command_blocking(); } - hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNASY,1\0"); - wait_register_response(); setup_complete = true; } @@ -467,7 +451,8 @@ void AP_ExternalAHRS_VectorNav::update_thread() { } } -const char *AP_ExternalAHRS_VectorNav::get_name() const { +const char* AP_ExternalAHRS_VectorNav::get_name() const +{ if (setup_complete) { return model_name; } @@ -477,11 +462,12 @@ const char *AP_ExternalAHRS_VectorNav::get_name() const { /* process INS mode INS packet */ -void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { +void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) +{ const struct VN_INS_packet1 &pkt1 = *(struct VN_INS_packet1 *)b; const struct VN_INS_packet2 &pkt2 = *last_ins_pkt2; - last_pkt1_ms = AP_HAL::millis(); + last_pkt1_ms = AP_HAL::millis(); *last_ins_pkt1 = pkt1; const bool use_uncomp = option_is_set(AP_ExternalAHRS::OPTIONS::VN_UNCOMP_IMU); @@ -490,32 +476,31 @@ void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { WITH_SEMAPHORE(state.sem); if (use_uncomp) { state.accel = Vector3f{pkt1.uncompAccel[0], pkt1.uncompAccel[1], pkt1.uncompAccel[2]}; - state.gyro = - Vector3f{pkt1.uncompAngRate[0], pkt1.uncompAngRate[1], pkt1.uncompAngRate[2]}; + state.gyro = Vector3f{pkt1.uncompAngRate[0], pkt1.uncompAngRate[1], pkt1.uncompAngRate[2]}; } else { state.accel = Vector3f{pkt1.accel[0], pkt1.accel[1], pkt1.accel[2]}; - state.gyro = Vector3f{pkt1.gyro[0], pkt1.gyro[1], pkt1.gyro[2]}; + state.gyro = Vector3f{pkt1.gyro[0], pkt1.gyro[1], pkt1.gyro[2]}; } - state.quat = Quaternion{pkt1.quaternion[3], pkt1.quaternion[0], pkt1.quaternion[1], - pkt1.quaternion[2]}; + state.quat = Quaternion{pkt1.quaternion[3], pkt1.quaternion[0], pkt1.quaternion[1], pkt1.quaternion[2]}; state.have_quaternion = true; - state.velocity = Vector3f{pkt1.velNED[0], pkt1.velNED[1], pkt1.velNED[2]}; + state.velocity = Vector3f{pkt1.velNED[0], pkt1.velNED[1], pkt1.velNED[2]}; state.have_velocity = true; - state.location = - Location{int32_t(pkt1.positionLLA[0] * 1.0e7), int32_t(pkt1.positionLLA[1] * 1.0e7), - int32_t(pkt1.positionLLA[2] * 1.0e2), Location::AltFrame::ABSOLUTE}; + state.location = Location{int32_t(pkt1.positionLLA[0] * 1.0e7), + int32_t(pkt1.positionLLA[1] * 1.0e7), + int32_t(pkt1.positionLLA[2] * 1.0e2), + Location::AltFrame::ABSOLUTE}; state.last_location_update_us = AP_HAL::micros(); - state.have_location = true; + state.have_location = true; } #if AP_BARO_EXTERNALAHRS_ENABLED { AP_ExternalAHRS::baro_data_message_t baro; - baro.instance = 0; - baro.pressure_pa = pkt1.pressure * 1e3; + baro.instance = 0; + baro.pressure_pa = pkt1.pressure*1e3; baro.temperature = pkt2.temp; AP::baro().handle_external(baro); @@ -526,7 +511,7 @@ void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { { AP_ExternalAHRS::mag_data_message_t mag; mag.field = Vector3f{pkt1.mag[0], pkt1.mag[1], pkt1.mag[2]}; - mag.field *= 1000; // to mGauss + mag.field *= 1000; // to mGauss AP::compass().handle_external(mag); } @@ -535,8 +520,8 @@ void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { { AP_ExternalAHRS::ins_data_message_t ins; - ins.accel = state.accel; - ins.gyro = state.gyro; + ins.accel = state.accel; + ins.gyro = state.gyro; ins.temperature = pkt2.temp; AP::ins().handle_external(ins); @@ -546,41 +531,43 @@ void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { /* process INS mode GNSS packet */ -void AP_ExternalAHRS_VectorNav::process_ins_packet2(const uint8_t *b) { +void AP_ExternalAHRS_VectorNav::process_ins_packet2(const uint8_t *b) +{ const struct VN_INS_packet2 &pkt2 = *(struct VN_INS_packet2 *)b; const struct VN_INS_packet1 &pkt1 = *last_ins_pkt1; - last_pkt2_ms = AP_HAL::millis(); + last_pkt2_ms = AP_HAL::millis(); *last_ins_pkt2 = pkt2; AP_ExternalAHRS::gps_data_message_t gps; // get ToW in milliseconds - gps.gps_week = pkt2.timeGPS / (AP_MSEC_PER_WEEK * 1000000ULL); - gps.ms_tow = (pkt2.timeGPS / 1000000ULL) % (60 * 60 * 24 * 7 * 1000ULL); - gps.fix_type = pkt2.GPS1Fix; + gps.gps_week = pkt2.timeGPS / (AP_MSEC_PER_WEEK * 1000000ULL); + gps.ms_tow = (pkt2.timeGPS / 1000000ULL) % (60*60*24*7*1000ULL); + gps.fix_type = pkt2.GPS1Fix; gps.satellites_in_view = pkt2.numGPS1Sats; gps.horizontal_pos_accuracy = pkt1.posU; - gps.vertical_pos_accuracy = pkt1.posU; + gps.vertical_pos_accuracy = pkt1.posU; gps.horizontal_vel_accuracy = pkt1.velU; gps.hdop = pkt2.GPS1DOP[4]; gps.vdop = pkt2.GPS1DOP[3]; - gps.latitude = pkt2.GPS1posLLA[0] * 1.0e7; - gps.longitude = pkt2.GPS1posLLA[1] * 1.0e7; + gps.latitude = pkt2.GPS1posLLA[0] * 1.0e7; + gps.longitude = pkt2.GPS1posLLA[1] * 1.0e7; gps.msl_altitude = pkt2.GPS1posLLA[2] * 1.0e2; gps.ned_vel_north = pkt2.GPS1velNED[0]; - gps.ned_vel_east = pkt2.GPS1velNED[1]; - gps.ned_vel_down = pkt2.GPS1velNED[2]; + gps.ned_vel_east = pkt2.GPS1velNED[1]; + gps.ned_vel_down = pkt2.GPS1velNED[2]; if (gps.fix_type >= 3 && !state.have_origin) { WITH_SEMAPHORE(state.sem); - state.origin = - Location{int32_t(pkt2.GPS1posLLA[0] * 1.0e7), int32_t(pkt2.GPS1posLLA[1] * 1.0e7), - int32_t(pkt2.GPS1posLLA[2] * 1.0e2), Location::AltFrame::ABSOLUTE}; + state.origin = Location{int32_t(pkt2.GPS1posLLA[0] * 1.0e7), + int32_t(pkt2.GPS1posLLA[1] * 1.0e7), + int32_t(pkt2.GPS1posLLA[2] * 1.0e2), + Location::AltFrame::ABSOLUTE}; state.have_origin = true; } uint8_t instance; @@ -592,7 +579,8 @@ void AP_ExternalAHRS_VectorNav::process_ins_packet2(const uint8_t *b) { /* process AHRS mode AHRS packet */ -void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { +void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) +{ const struct VN_AHRS_packet1 &pkt = *(struct VN_AHRS_packet1 *)b; last_pkt1_ms = AP_HAL::millis(); @@ -606,19 +594,18 @@ void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { state.gyro = Vector3f{pkt.uncompAngRate[0], pkt.uncompAngRate[1], pkt.uncompAngRate[2]}; } else { state.accel = Vector3f{pkt.accel[0], pkt.accel[1], pkt.accel[2]}; - state.gyro = Vector3f{pkt.gyro[0], pkt.gyro[1], pkt.gyro[2]}; + state.gyro = Vector3f{pkt.gyro[0], pkt.gyro[1], pkt.gyro[2]}; } - state.quat = - Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]}; + state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]}; state.have_quaternion = true; } #if AP_BARO_EXTERNALAHRS_ENABLED { AP_ExternalAHRS::baro_data_message_t baro; - baro.instance = 0; - baro.pressure_pa = pkt.pressure * 1e3; + baro.instance = 0; + baro.pressure_pa = pkt.pressure*1e3; baro.temperature = pkt.temp; AP::baro().handle_external(baro); @@ -633,7 +620,7 @@ void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { } else { mag.field = Vector3f{pkt.mag[0], pkt.mag[1], pkt.mag[2]}; } - mag.field *= 1000; // to mGauss + mag.field *= 1000; // to mGauss AP::compass().handle_external(mag); } @@ -642,8 +629,8 @@ void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { { AP_ExternalAHRS::ins_data_message_t ins; - ins.accel = state.accel; - ins.gyro = state.gyro; + ins.accel = state.accel; + ins.gyro = state.gyro; ins.temperature = pkt.temp; AP::ins().handle_external(ins); @@ -669,18 +656,24 @@ void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { // @Field: Q3: Attitude quaternion 3 // @Field: Q4: Attitude quaternion 4 - AP::logger().WriteStreaming( - "EAH3", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ,Q1,Q2,Q3,Q4", "sdPGGGoooEEE----", - "F000000000000000", "Qfffffffffffffff", AP_HAL::micros64(), pkt.temp, pkt.pressure * 1e3, - use_uncomp ? pkt.uncompMag[0] : pkt.mag[0], use_uncomp ? pkt.uncompMag[1] : pkt.mag[1], - use_uncomp ? pkt.uncompMag[2] : pkt.mag[2], state.accel[0], state.accel[1], state.accel[2], - state.gyro[0], state.gyro[1], state.gyro[2], state.quat[0], state.quat[1], state.quat[2], - state.quat[3]); + AP::logger().WriteStreaming("EAH3", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ,Q1,Q2,Q3,Q4", + "sdPGGGoooEEE----", "F000000000000000", + "Qfffffffffffffff", + AP_HAL::micros64(), + pkt.temp, pkt.pressure*1e3, + use_uncomp ? pkt.uncompMag[0] : pkt.mag[0], + use_uncomp ? pkt.uncompMag[1] : pkt.mag[1], + use_uncomp ? pkt.uncompMag[2] : pkt.mag[2], + state.accel[0], state.accel[1], state.accel[2], + state.gyro[0], state.gyro[1], state.gyro[2], + state.quat[0], state.quat[1], state.quat[2], state.quat[3]); #endif // HAL_LOGGING_ENABLED } + // get serial port number for the uart -int8_t AP_ExternalAHRS_VectorNav::get_port(void) const { +int8_t AP_ExternalAHRS_VectorNav::get_port(void) const +{ if (!uart) { return -1; } @@ -688,7 +681,8 @@ int8_t AP_ExternalAHRS_VectorNav::get_port(void) const { }; // accessors for AP_AHRS -bool AP_ExternalAHRS_VectorNav::healthy(void) const { +bool AP_ExternalAHRS_VectorNav::healthy(void) const +{ const uint32_t now = AP_HAL::millis(); if (type == TYPE::VN_AHRS) { return (now - last_pkt1_ms < 40); @@ -696,7 +690,8 @@ bool AP_ExternalAHRS_VectorNav::healthy(void) const { return (now - last_pkt1_ms < 40 && now - last_pkt2_ms < 500); } -bool AP_ExternalAHRS_VectorNav::initialised(void) const { +bool AP_ExternalAHRS_VectorNav::initialised(void) const +{ if (!setup_complete) { return false; } @@ -706,7 +701,8 @@ bool AP_ExternalAHRS_VectorNav::initialised(void) const { return last_pkt1_ms != 0 && last_pkt2_ms != 0; } -bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const { +bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const +{ if (!setup_complete) { hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav setup failed"); return false; @@ -732,7 +728,8 @@ bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure get filter status. We don't know the meaning of the status bits yet, so assume all OK if we have GPS lock */ -void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const { +void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const +{ memset(&status, 0, sizeof(status)); if (type == TYPE::VN_INS) { if (last_ins_pkt1 && last_ins_pkt2) { @@ -745,12 +742,12 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con const struct VN_INS_packet2 &pkt2 = *last_ins_pkt2; if (pkt2.GPS1Fix >= 3) { - status.flags.horiz_vel = true; - status.flags.horiz_pos_rel = true; - status.flags.horiz_pos_abs = true; + status.flags.horiz_vel = true; + status.flags.horiz_pos_rel = true; + status.flags.horiz_pos_abs = true; status.flags.pred_horiz_pos_rel = true; status.flags.pred_horiz_pos_abs = true; - status.flags.using_gps = true; + status.flags.using_gps = true; } } } else { @@ -762,7 +759,8 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con } // send an EKF_STATUS message to GCS -void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const { +void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const +{ if (!last_ins_pkt1) { return; } @@ -806,12 +804,13 @@ void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const { // send message const struct VN_INS_packet1 &pkt1 = *(struct VN_INS_packet1 *)last_ins_pkt1; - const float vel_gate = 5; - const float pos_gate = 5; - const float hgt_gate = 5; - const float mag_var = 0; - mavlink_msg_ekf_status_report_send(link.get_chan(), flags, pkt1.velU / vel_gate, - pkt1.posU / pos_gate, pkt1.posU / hgt_gate, mag_var, 0, 0); + const float vel_gate = 5; + const float pos_gate = 5; + const float hgt_gate = 5; + const float mag_var = 0; + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, + pkt1.velU/vel_gate, pkt1.posU/pos_gate, pkt1.posU/hgt_gate, + mag_var, 0, 0); } #endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 8e5e40de94729d..b6f4216b55a731 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -25,7 +25,8 @@ #include "AP_ExternalAHRS_backend.h" class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { - public: + +public: AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state); // get serial port number, -1 for not enabled @@ -44,14 +45,14 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { } // Get model/type name - const char *get_name() const override; + const char* get_name() const override; + +protected: - protected: uint8_t num_gps_sensors(void) const override { return 1; } - - private: +private: AP_HAL::UARTDriver *uart; int8_t port_num; bool setup_complete; @@ -65,7 +66,7 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { void process_ins_packet1(const uint8_t *b); void process_ins_packet2(const uint8_t *b); void process_ahrs_packet(const uint8_t *b); - void wait_register_response(); + void send_command_blocking(); uint8_t *pktbuf; uint16_t pktoffset; @@ -78,27 +79,26 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { uint32_t last_pkt2_ms; enum class TYPE { - VN_INS, // Full INS mode, requiring GNSS. Used by VN-2X0 and VN-3X0 + VN_INS, // Full INS mode, requiring GNSS. Used by VN-2X0 and VN-3X0 VN_AHRS, // IMU-only mode, used by VN-1X0 } type; bool has_dual_gnss = false; char model_name[20]; - char message_to_send[50]; + char message_to_send[50]; // NMEA parsing for setup bool decode(char c); bool decode_latest_term(); struct NMEA_parser { - char term[20]; // buffer for the current term within the current sentence - uint8_t term_offset; // offset within the _term buffer where the next character should be - // placed - uint8_t term_number; // term index within the current sentence - uint8_t checksum; // checksum accumulator - bool term_is_checksum; // current term is the checksum - bool sentence_valid; // is current sentence valid so far - bool sentence_done; // true if this sentence has already been decoded + char term[20]; // buffer for the current term within the current sentence + uint8_t term_offset; // offset within the _term buffer where the next character should be placed + uint8_t term_number; // term index within the current sentence + uint8_t checksum; // checksum accumulator + bool term_is_checksum; // current term is the checksum + bool sentence_valid; // is current sentence valid so far + bool sentence_done; // true if this sentence has already been decoded } nmea; };