mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Logger: use ahrs singleton to log ATT, POS and AHRS2
This commit is contained in:
parent
d7132928d1
commit
c30873097a
@ -245,8 +245,8 @@ public:
|
||||
void Write_Rally();
|
||||
void Write_Baro(uint64_t time_us=0);
|
||||
void Write_Power(void);
|
||||
void Write_AHRS2(AP_AHRS &ahrs);
|
||||
void Write_POS(AP_AHRS &ahrs);
|
||||
void Write_AHRS2();
|
||||
void Write_POS();
|
||||
void Write_Radio(const mavlink_radio_t &packet);
|
||||
void Write_Message(const char *message);
|
||||
void Write_MessageF(const char *fmt, ...);
|
||||
@ -254,7 +254,7 @@ public:
|
||||
void Write_Camera(const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||
void Write_Trigger(const Location ¤t_loc);
|
||||
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot);
|
||||
void Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
||||
void Write_Attitude(const Vector3f &targets);
|
||||
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Write_Current();
|
||||
void Write_Compass(uint64_t time_us=0);
|
||||
|
@ -488,8 +488,9 @@ void AP_Logger::Write_Power(void)
|
||||
}
|
||||
|
||||
// Write an AHRS2 packet
|
||||
void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
|
||||
void AP_Logger::Write_AHRS2()
|
||||
{
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
Vector3f euler;
|
||||
struct Location loc;
|
||||
Quaternion quat;
|
||||
@ -514,8 +515,10 @@ void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
|
||||
}
|
||||
|
||||
// Write a POS packet
|
||||
void AP_Logger::Write_POS(AP_AHRS &ahrs)
|
||||
void AP_Logger::Write_POS()
|
||||
{
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
|
||||
Location loc;
|
||||
if (!ahrs.get_position(loc)) {
|
||||
return;
|
||||
@ -600,8 +603,10 @@ void AP_Logger::Write_Trigger(const Location ¤t_loc)
|
||||
}
|
||||
|
||||
// Write an attitude packet
|
||||
void AP_Logger::Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
|
||||
void AP_Logger::Write_Attitude(const Vector3f &targets)
|
||||
{
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
|
||||
const struct log_Attitude pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
|
Loading…
Reference in New Issue
Block a user