mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Tools: Replay: use Log_Write for CHEK message
This commit is contained in:
parent
deeaf6ec09
commit
961aac454b
@ -31,12 +31,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
const struct LogStructure log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_CHEK_MSG, sizeof(log_Chek),
|
||||
"CHEK",
|
||||
"QccCLLffff",
|
||||
"TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD",
|
||||
"sdddDUmnnn",
|
||||
"FBBBGGB000"}
|
||||
};
|
||||
|
||||
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass, AP_GPS &_gps,
|
||||
|
@ -724,21 +724,23 @@ void Replay::log_check_generate(void)
|
||||
_vehicle.EKF2.getVelNED(-1,velocity);
|
||||
_vehicle.EKF2.getLLH(loc);
|
||||
|
||||
struct log_Chek packet = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CHEK_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
|
||||
pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
|
||||
yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
|
||||
lat : loc.lat,
|
||||
lng : loc.lng,
|
||||
alt : loc.alt*0.01f,
|
||||
vnorth : velocity.x,
|
||||
veast : velocity.y,
|
||||
vdown : velocity.z
|
||||
_vehicle.dataflash.Log_Write(
|
||||
"CHEK",
|
||||
"TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD",
|
||||
"sdddDUmnnn",
|
||||
"FBBBGGB000",
|
||||
"QccCLLffff",
|
||||
AP_HAL::micros64(),
|
||||
(int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
|
||||
(int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
|
||||
(uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
|
||||
loc.lat,
|
||||
loc.lng,
|
||||
loc.alt*0.01f,
|
||||
velocity.x,
|
||||
velocity.y,
|
||||
velocity.z
|
||||
};
|
||||
|
||||
_vehicle.dataflash.WriteBlock(&packet, sizeof(packet));
|
||||
}
|
||||
|
||||
|
||||
|
@ -180,10 +180,6 @@ private:
|
||||
FILE *xfopen(const char *f, const char *mode);
|
||||
};
|
||||
|
||||
enum {
|
||||
LOG_CHEK_MSG=100
|
||||
};
|
||||
|
||||
/*
|
||||
Replay specific log structures
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user