mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: Remove external event from GPS data stream
If the event pin floats, this can lead to UART congestion, causing the EKF to reject the GPS data, and the vehicle will drift around the sky in a most disturbing manner
This commit is contained in:
parent
cb88bc7f53
commit
32c583bd20
|
@ -22,7 +22,6 @@
|
|||
|
||||
#include "AP_GPS.h"
|
||||
#include "AP_GPS_SBF.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -234,35 +233,6 @@ AP_GPS_SBF::parse(uint8_t temp)
|
|||
return false;
|
||||
}
|
||||
|
||||
void
|
||||
AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp)
|
||||
{
|
||||
if (!should_log()) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
|
||||
struct log_GPS_SBF_EVENT header = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_GPS_SBF_EVENT_MSG),
|
||||
time_us:now,
|
||||
TOW:temp.TOW,
|
||||
WNc:temp.WNc,
|
||||
Mode:temp.Mode,
|
||||
Error:temp.Error,
|
||||
Latitude:temp.Latitude*RAD_TO_DEG_DOUBLE,
|
||||
Longitude:temp.Longitude*RAD_TO_DEG_DOUBLE,
|
||||
Height:temp.Height,
|
||||
Undulation:temp.Undulation,
|
||||
Vn:temp.Vn,
|
||||
Ve:temp.Ve,
|
||||
Vu:temp.Vu,
|
||||
COG:temp.COG
|
||||
};
|
||||
|
||||
AP::logger().WriteBlock(&header, sizeof(header));
|
||||
}
|
||||
|
||||
bool
|
||||
AP_GPS_SBF::process_message(void)
|
||||
{
|
||||
|
@ -271,9 +241,6 @@ AP_GPS_SBF::process_message(void)
|
|||
Debug("BlockID %d", blockid);
|
||||
|
||||
switch (blockid) {
|
||||
case ExtEventPVTGeodetic:
|
||||
log_ExtEventPVTGeodetic(sbf_msg.data.msg4007u);
|
||||
break;
|
||||
case PVTGeodetic:
|
||||
{
|
||||
const msg4007 &temp = sbf_msg.data.msg4007u;
|
||||
|
|
|
@ -62,7 +62,7 @@ private:
|
|||
uint8_t _init_blob_index = 0;
|
||||
uint32_t _init_blob_time = 0;
|
||||
const char* _initialisation_blob[5] = {
|
||||
"sso, Stream1, COM1, PVTGeodetic+DOP+ExtEventPVTGeodetic+ReceiverStatus+VelCovGeodetic, msec100\n",
|
||||
"sso, Stream1, COM1, PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic, msec100\n",
|
||||
"srd, Moderate, UAV\n",
|
||||
"sem, PVT, 5\n",
|
||||
"spm, Rover, all\n",
|
||||
|
@ -83,7 +83,6 @@ private:
|
|||
DOP = 4001,
|
||||
PVTGeodetic = 4007,
|
||||
ReceiverStatus = 4014,
|
||||
ExtEventPVTGeodetic = 4038,
|
||||
VelCovGeodetic = 5908
|
||||
};
|
||||
|
||||
|
@ -196,10 +195,8 @@ private:
|
|||
uint16_t read;
|
||||
} sbf_msg;
|
||||
|
||||
void log_ExtEventPVTGeodetic(const msg4007 &temp);
|
||||
|
||||
enum {
|
||||
SOFTWARE = (1 << 3), // set upon detection of a software warning or error. This bit is reset by the command “lif, error”
|
||||
SOFTWARE = (1 << 3), // set upon detection of a software warning or error. This bit is reset by the command lif, error
|
||||
WATCHDOG = (1 << 4), // set when the watch-dog expired at least once since the last power-on.
|
||||
CONGESTION = (1 << 6), // set when an output data congestion has been detected on at least one of the communication ports of the receiver during the last second.
|
||||
MISSEDEVENT = (1 << 8), // set when an external event congestion has been detected during the last second. It indicates that the receiver is receiving too many events on its EVENTx pins.
|
||||
|
|
Loading…
Reference in New Issue