AP_Logger: move LogOriginType into AP_AHRS
only used to log the origins by the AHRS library
This commit is contained in:
parent
1dd34d87e7
commit
66d8be825f
@ -430,7 +430,7 @@ public:
|
||||
ekf_origin = 0,
|
||||
ahrs_home = 1
|
||||
};
|
||||
void Write_Origin(uint8_t origin_type, const Location &loc) const;
|
||||
void Write_Origin(LogOriginType origin_type, const Location &loc) const;
|
||||
void Write_POS(void) const;
|
||||
|
||||
// return a smoothed and corrected gyro vector in radians/second
|
||||
|
@ -63,12 +63,12 @@ void AP_AHRS::Write_Attitude(const Vector3f &targets) const
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_AHRS::Write_Origin(uint8_t origin_type, const Location &loc) const
|
||||
void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const
|
||||
{
|
||||
const struct log_ORGN pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
origin_type : origin_type,
|
||||
origin_type : (uint8_t)origin_type,
|
||||
latitude : loc.lat,
|
||||
longitude : loc.lng,
|
||||
altitude : loc.alt
|
||||
|
@ -1433,8 +1433,3 @@ enum LogMessages : uint8_t {
|
||||
|
||||
static_assert(_LOG_LAST_MSG_ <= 255, "Too many message formats");
|
||||
static_assert(LOG_MODE_MSG < 128, "Duplicate message format IDs");
|
||||
|
||||
enum LogOriginType {
|
||||
ekf_origin = 0,
|
||||
ahrs_home = 1
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user