mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_ExternalAHRS_VectorNav: Address review comments
Remove unnecessary header Switch parameters to default initialization Change pointer casting to prevent a const_cast, and remove doubled sync byte when echoing ASCII messages Fix Valgrind report by preventing use of nmea_printf on buffers which may not be null-terminated
This commit is contained in:
parent
50980ee03e
commit
1d1bb5724e
@ -16,7 +16,6 @@
|
||||
support for serial connected AHRS systems
|
||||
*/
|
||||
|
||||
#include <cstdint>
|
||||
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
||||
|
||||
#include "AP_ExternalAHRS_config.h"
|
||||
|
@ -73,13 +73,13 @@ private:
|
||||
uint16_t pktoffset;
|
||||
uint16_t bufsize;
|
||||
|
||||
struct VN_imu_packet *latest_imu_packet = nullptr;
|
||||
struct VN_INS_ekf_packet *latest_ins_ekf_packet = nullptr;
|
||||
struct VN_INS_gnss_packet *latest_ins_gnss_packet = nullptr;
|
||||
struct VN_imu_packet *latest_imu_packet;
|
||||
struct VN_INS_ekf_packet *latest_ins_ekf_packet;
|
||||
struct VN_INS_gnss_packet *latest_ins_gnss_packet;
|
||||
|
||||
uint32_t last_pkt1_ms = UINT32_MAX;
|
||||
uint32_t last_pkt2_ms = UINT32_MAX;
|
||||
uint32_t last_pkt3_ms = UINT32_MAX;
|
||||
uint32_t last_pkt1_ms;
|
||||
uint32_t last_pkt2_ms;
|
||||
uint32_t last_pkt3_ms;
|
||||
|
||||
enum class TYPE {
|
||||
VN_INS, // Full INS mode, requiring GNSS. Used by VN-2X0 and VN-3X0
|
||||
|
@ -129,16 +129,16 @@ void VectorNav::send_imu_packet(void)
|
||||
pkt.pressure = pressure_Pa*0.001 + rand_float() * 0.01;
|
||||
|
||||
const uint8_t sync_byte = 0xFA;
|
||||
write_to_autopilot((char *)&sync_byte, 1);
|
||||
write_to_autopilot((char *)&VN_IMU_packet_sim::header, sizeof(VN_IMU_packet_sim::header));
|
||||
write_to_autopilot((char *)&pkt, sizeof(pkt));
|
||||
write_to_autopilot((const char *)&sync_byte, 1);
|
||||
write_to_autopilot((const char *)&VN_IMU_packet_sim::header, sizeof(VN_IMU_packet_sim::header));
|
||||
write_to_autopilot((const char *)&pkt, sizeof(pkt));
|
||||
|
||||
uint16_t crc = crc16_ccitt(&VN_IMU_packet_sim::header[0], sizeof(VN_IMU_packet_sim::header), 0);
|
||||
crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc);
|
||||
uint16_t crc2;
|
||||
swab(&crc, &crc2, 2);
|
||||
|
||||
write_to_autopilot((char *)&crc2, sizeof(crc2));
|
||||
write_to_autopilot((const char *)&crc2, sizeof(crc2));
|
||||
}
|
||||
|
||||
void VectorNav::send_ins_ekf_packet(void)
|
||||
@ -174,9 +174,9 @@ void VectorNav::send_ins_ekf_packet(void)
|
||||
pkt.velU = 0.25;
|
||||
|
||||
const uint8_t sync_byte = 0xFA;
|
||||
write_to_autopilot((char *)&sync_byte, 1);
|
||||
write_to_autopilot((char *)&VN_INS_ekf_packet_sim::header, sizeof(VN_INS_ekf_packet_sim::header));
|
||||
write_to_autopilot((char *)&pkt, sizeof(pkt));
|
||||
write_to_autopilot((const char *)&sync_byte, 1);
|
||||
write_to_autopilot((const char *)&VN_INS_ekf_packet_sim::header, sizeof(VN_INS_ekf_packet_sim::header));
|
||||
write_to_autopilot((const char *)&pkt, sizeof(pkt));
|
||||
|
||||
uint16_t crc = crc16_ccitt(&VN_INS_ekf_packet_sim::header[0], sizeof(VN_INS_ekf_packet_sim::header), 0);
|
||||
crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc);
|
||||
@ -184,7 +184,7 @@ void VectorNav::send_ins_ekf_packet(void)
|
||||
uint16_t crc2;
|
||||
swab(&crc, &crc2, 2);
|
||||
|
||||
write_to_autopilot((char *)&crc2, sizeof(crc2));
|
||||
write_to_autopilot((const char *)&crc2, sizeof(crc2));
|
||||
}
|
||||
|
||||
void VectorNav::send_ins_gnss_packet(void)
|
||||
@ -221,9 +221,9 @@ void VectorNav::send_ins_gnss_packet(void)
|
||||
pkt.fix2 = 3;
|
||||
|
||||
const uint8_t sync_byte = 0xFA;
|
||||
write_to_autopilot((char *)&sync_byte, 1);
|
||||
write_to_autopilot((char *)&VN_INS_gnss_packet_sim::header, sizeof(VN_INS_gnss_packet_sim::header));
|
||||
write_to_autopilot((char *)&pkt, sizeof(pkt));
|
||||
write_to_autopilot((const char *)&sync_byte, 1);
|
||||
write_to_autopilot((const char *)&VN_INS_gnss_packet_sim::header, sizeof(VN_INS_gnss_packet_sim::header));
|
||||
write_to_autopilot((const char *)&pkt, sizeof(pkt));
|
||||
|
||||
uint16_t crc = crc16_ccitt(&VN_INS_gnss_packet_sim::header[0], sizeof(VN_INS_gnss_packet_sim::header), 0);
|
||||
crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc);
|
||||
@ -231,7 +231,7 @@ void VectorNav::send_ins_gnss_packet(void)
|
||||
uint16_t crc2;
|
||||
swab(&crc, &crc2, 2);
|
||||
|
||||
write_to_autopilot((char *)&crc2, sizeof(crc2));
|
||||
write_to_autopilot((const char *)&crc2, sizeof(crc2));
|
||||
}
|
||||
|
||||
void VectorNav::nmea_printf(const char *fmt, ...)
|
||||
|
Loading…
Reference in New Issue
Block a user