mirror of https://github.com/ArduPilot/ardupilot
SITL: remove trailing whitespace in SITL GPS drivers
we've just lost the history for these lines anyway
This commit is contained in:
parent
d992ead5b1
commit
a143d2e453
|
@ -73,7 +73,7 @@ void GPS_NMEA::publish(const GPS_Data *d)
|
|||
d->have_lock?_sitl->gps_numsats[instance]:3,
|
||||
1.2,
|
||||
d->altitude);
|
||||
|
||||
|
||||
const float speed_mps = d->speed_2d();
|
||||
const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS;
|
||||
const auto heading_rad = d->heading();
|
||||
|
|
|
@ -92,20 +92,20 @@ void GPS_NOVA::publish(const GPS_Data *d)
|
|||
double vertspd;
|
||||
float resv;
|
||||
} bestvel {};
|
||||
|
||||
|
||||
const auto gps_tow = gps_time();
|
||||
|
||||
|
||||
header.preamble[0] = 0xaa;
|
||||
header.preamble[1] = 0x44;
|
||||
header.preamble[2] = 0x12;
|
||||
header.headerlength = sizeof(header);
|
||||
header.week = gps_tow.week;
|
||||
header.tow = gps_tow.ms;
|
||||
|
||||
|
||||
header.messageid = 174;
|
||||
header.messagelength = sizeof(psrdop);
|
||||
header.sequence += 1;
|
||||
|
||||
|
||||
psrdop.hdop = 1.20;
|
||||
psrdop.htdop = 1.20;
|
||||
nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&psrdop, sizeof(psrdop));
|
||||
|
@ -114,8 +114,8 @@ void GPS_NOVA::publish(const GPS_Data *d)
|
|||
header.messageid = 99;
|
||||
header.messagelength = sizeof(bestvel);
|
||||
header.sequence += 1;
|
||||
|
||||
bestvel.horspd = norm(d->speedN, d->speedE);
|
||||
|
||||
bestvel.horspd = norm(d->speedN, d->speedE);
|
||||
bestvel.trkgnd = ToDeg(atan2f(d->speedE, d->speedN));
|
||||
bestvel.vertspd = -d->speedD;
|
||||
|
||||
|
@ -125,7 +125,7 @@ void GPS_NOVA::publish(const GPS_Data *d)
|
|||
header.messageid = 42;
|
||||
header.messagelength = sizeof(bestpos);
|
||||
header.sequence += 1;
|
||||
|
||||
|
||||
bestpos.lat = d->latitude;
|
||||
bestpos.lng = d->longitude;
|
||||
bestpos.hgt = d->altitude;
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
using namespace SITL;
|
||||
|
||||
void GPS_GSOF::publish(const GPS_Data *d)
|
||||
{
|
||||
{
|
||||
// This logic is to populate output buffer only with enabled channels.
|
||||
// It also only sends each channel at the configured rate.
|
||||
const uint64_t now = AP_HAL::millis();
|
||||
|
@ -98,7 +98,7 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
bootcount
|
||||
};
|
||||
static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN);
|
||||
|
||||
|
||||
payload_sz += sizeof(pos_time);
|
||||
memcpy(&buf[offset], &pos_time, sizeof(pos_time));
|
||||
offset += sizeof(pos_time);
|
||||
|
@ -126,8 +126,8 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE),
|
||||
gsof_pack_double(static_cast<double>(d->altitude))
|
||||
};
|
||||
static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN);
|
||||
|
||||
static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN);
|
||||
|
||||
payload_sz += sizeof(pos);
|
||||
memcpy(&buf[offset], &pos, sizeof(pos));
|
||||
offset += sizeof(pos);
|
||||
|
@ -154,7 +154,7 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
RESERVED_6 = 1U << 6,
|
||||
RESERVED_7 = 1U << 7,
|
||||
};
|
||||
uint8_t vel_flags {0};
|
||||
uint8_t vel_flags {0};
|
||||
if(d->have_lock) {
|
||||
vel_flags |= uint8_t(VEL_FIELDS::VALID);
|
||||
vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS);
|
||||
|
@ -162,7 +162,7 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
}
|
||||
|
||||
const struct PACKED gsof_vel {
|
||||
const uint8_t OUTPUT_RECORD_TYPE;
|
||||
const uint8_t OUTPUT_RECORD_TYPE;
|
||||
const uint8_t RECORD_LEN;
|
||||
// https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags
|
||||
uint8_t flags;
|
||||
|
@ -194,7 +194,7 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
// https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12
|
||||
constexpr uint8_t GSOF_DOP_LEN = 0x10;
|
||||
const struct PACKED gsof_dop {
|
||||
const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) };
|
||||
const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) };
|
||||
const uint8_t RECORD_LEN { GSOF_DOP_LEN };
|
||||
uint32_t pdop = htobe32(1);
|
||||
uint32_t hdop = htobe32(1);
|
||||
|
@ -223,7 +223,7 @@ void GPS_GSOF::publish(const GPS_Data *d)
|
|||
// https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_SIGMA.html
|
||||
constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26;
|
||||
const struct PACKED gsof_pos_sigma {
|
||||
const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) };
|
||||
const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) };
|
||||
const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN };
|
||||
uint32_t pos_rms = htobe32(0);
|
||||
uint32_t sigma_e = htobe32(0);
|
||||
|
@ -365,7 +365,7 @@ bool DCOL_Parser::parse_cmd_appfile() {
|
|||
if (expected_payload_length < min_cmd_appfile_sz) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// For now, ignore appfile_trans_num, return success regardless.
|
||||
// If the driver doesn't send the right value, it's not clear what the behavior is supposed to be.
|
||||
// Also would need to handle re-sync.
|
||||
|
@ -475,7 +475,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size)
|
|||
static uint8_t TRANSMISSION_NUMBER = 0; // Functionally, this is a sequence number
|
||||
// Most messages, even GSOF49, only take one page. For SIM, assume it.
|
||||
assert(size < 0xFA); // GPS SIM doesn't yet support paging
|
||||
constexpr uint8_t PAGE_INDEX = 0;
|
||||
constexpr uint8_t PAGE_INDEX = 0;
|
||||
constexpr uint8_t MAX_PAGE_INDEX = 0;
|
||||
const uint8_t gsof_header[3] = {
|
||||
TRANSMISSION_NUMBER,
|
||||
|
@ -496,7 +496,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size)
|
|||
// This aligns with manual's idea of data bytes:
|
||||
// "Each message begins with a 4-byte header, followed by the bytes of data in each packet. The packet ends with a 2-byte trailer."
|
||||
// Thus, for this implementation with single-page single-record per DCOL packet,
|
||||
// the length is simply the sum of data packet size, the gsof_header size.
|
||||
// the length is simply the sum of data packet size, the gsof_header size.
|
||||
const uint8_t length = size + sizeof(gsof_header);
|
||||
const uint8_t dcol_header[4] {
|
||||
STX,
|
||||
|
|
|
@ -99,27 +99,27 @@ void GPS_UBlox::publish(const GPS_Data *d)
|
|||
uint16_t eDOP;
|
||||
} dop {};
|
||||
struct PACKED ubx_nav_pvt {
|
||||
uint32_t itow;
|
||||
uint16_t year;
|
||||
uint8_t month, day, hour, min, sec;
|
||||
uint8_t valid;
|
||||
uint32_t t_acc;
|
||||
int32_t nano;
|
||||
uint8_t fix_type;
|
||||
uint8_t flags;
|
||||
uint8_t flags2;
|
||||
uint8_t num_sv;
|
||||
int32_t lon, lat;
|
||||
int32_t height, h_msl;
|
||||
uint32_t h_acc, v_acc;
|
||||
int32_t velN, velE, velD, gspeed;
|
||||
int32_t head_mot;
|
||||
uint32_t s_acc;
|
||||
uint32_t head_acc;
|
||||
uint16_t p_dop;
|
||||
uint8_t reserved1[6];
|
||||
uint32_t itow;
|
||||
uint16_t year;
|
||||
uint8_t month, day, hour, min, sec;
|
||||
uint8_t valid;
|
||||
uint32_t t_acc;
|
||||
int32_t nano;
|
||||
uint8_t fix_type;
|
||||
uint8_t flags;
|
||||
uint8_t flags2;
|
||||
uint8_t num_sv;
|
||||
int32_t lon, lat;
|
||||
int32_t height, h_msl;
|
||||
uint32_t h_acc, v_acc;
|
||||
int32_t velN, velE, velD, gspeed;
|
||||
int32_t head_mot;
|
||||
uint32_t s_acc;
|
||||
uint32_t head_acc;
|
||||
uint16_t p_dop;
|
||||
uint8_t reserved1[6];
|
||||
uint32_t headVeh;
|
||||
uint8_t reserved2[4];
|
||||
uint8_t reserved2[4];
|
||||
} pvt {};
|
||||
const uint8_t SV_COUNT = 10;
|
||||
struct PACKED ubx_nav_svinfo {
|
||||
|
@ -234,20 +234,20 @@ void GPS_UBlox::publish(const GPS_Data *d)
|
|||
dop.hDOP = 121;
|
||||
dop.nDOP = 65535;
|
||||
dop.eDOP = 65535;
|
||||
|
||||
|
||||
pvt.itow = gps_tow.ms;
|
||||
pvt.year = 0;
|
||||
pvt.year = 0;
|
||||
pvt.month = 0;
|
||||
pvt.day = 0;
|
||||
pvt.hour = 0;
|
||||
pvt.min = 0;
|
||||
pvt.sec = 0;
|
||||
pvt.sec = 0;
|
||||
pvt.valid = 0; // invalid utc date
|
||||
pvt.t_acc = 0;
|
||||
pvt.nano = 0;
|
||||
pvt.t_acc = 0;
|
||||
pvt.nano = 0;
|
||||
pvt.fix_type = d->have_lock? 0x3 : 0;
|
||||
pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok
|
||||
pvt.flags2 =0;
|
||||
pvt.flags2 =0;
|
||||
pvt.num_sv = d->have_lock ? _sitl->gps_numsats[instance] : 3;
|
||||
pvt.lon = d->longitude * 1.0e7;
|
||||
pvt.lat = d->latitude * 1.0e7;
|
||||
|
@ -258,11 +258,11 @@ void GPS_UBlox::publish(const GPS_Data *d)
|
|||
pvt.velN = 1000.0f * d->speedN;
|
||||
pvt.velE = 1000.0f * d->speedE;
|
||||
pvt.velD = 1000.0f * d->speedD;
|
||||
pvt.gspeed = norm(d->speedN, d->speedE) * 1000;
|
||||
pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5;
|
||||
pvt.s_acc = 40;
|
||||
pvt.head_acc = 38 * 1.0e5;
|
||||
pvt.p_dop = 65535;
|
||||
pvt.gspeed = norm(d->speedN, d->speedE) * 1000;
|
||||
pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5;
|
||||
pvt.s_acc = 40;
|
||||
pvt.head_acc = 38 * 1.0e5;
|
||||
pvt.p_dop = 65535;
|
||||
memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1));
|
||||
pvt.headVeh = 0;
|
||||
memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2));
|
||||
|
|
Loading…
Reference in New Issue