mirror of https://github.com/ArduPilot/ardupilot
Rover: move wheelEncoder logging to library
This commit is contained in:
parent
3f58461839
commit
d5c67e0b07
|
@ -245,7 +245,7 @@ void Rover::update_logging2(void)
|
|||
|
||||
if (should_log(MASK_LOG_RC)) {
|
||||
Log_Write_RC();
|
||||
Log_Write_WheelEncoder();
|
||||
g2.wheel_encoder.Log_Write();
|
||||
}
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
|
|
|
@ -307,34 +307,6 @@ void Rover::Log_Write_RC(void)
|
|||
}
|
||||
}
|
||||
|
||||
// wheel encoder packet
|
||||
struct PACKED log_WheelEncoder {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
float distance_0;
|
||||
uint8_t quality_0;
|
||||
float distance_1;
|
||||
uint8_t quality_1;
|
||||
};
|
||||
|
||||
// log wheel encoder information
|
||||
void Rover::Log_Write_WheelEncoder()
|
||||
{
|
||||
// return immediately if no wheel encoders are enabled
|
||||
if (!g2.wheel_encoder.enabled(0) && !g2.wheel_encoder.enabled(1)) {
|
||||
return;
|
||||
}
|
||||
struct log_WheelEncoder pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_WHEELENCODER_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
distance_0 : g2.wheel_encoder.get_distance(0),
|
||||
quality_0 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(0), 0.0f, 100.0f),
|
||||
distance_1 : g2.wheel_encoder.get_distance(1),
|
||||
quality_1 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(1), 0.0f, 100.0f)
|
||||
};
|
||||
logger.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void Rover::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by AP_Logger
|
||||
|
@ -365,8 +337,6 @@ const LogStructure Rover::log_structure[] = {
|
|||
"GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
|
||||
{ LOG_ERROR_MSG, sizeof(log_Error),
|
||||
"ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" },
|
||||
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder),
|
||||
"WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" },
|
||||
};
|
||||
|
||||
void Rover::log_init(void)
|
||||
|
@ -389,7 +359,6 @@ void Rover::Log_Write_Throttle() {}
|
|||
void Rover::Log_Write_Rangefinder() {}
|
||||
void Rover::Log_Write_RC(void) {}
|
||||
void Rover::Log_Write_Steering() {}
|
||||
void Rover::Log_Write_WheelEncoder() {}
|
||||
void Rover::Log_Write_Vehicle_Startup_Messages() {}
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
|
|
|
@ -460,7 +460,6 @@ private:
|
|||
void Log_Write_Throttle();
|
||||
void Log_Write_Rangefinder();
|
||||
void Log_Write_RC(void);
|
||||
void Log_Write_WheelEncoder();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page);
|
||||
void log_init(void);
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#define LOG_ARM_DISARM_MSG 0x08
|
||||
#define LOG_STEERING_MSG 0x0D
|
||||
#define LOG_GUIDEDTARGET_MSG 0x0E
|
||||
#define LOG_WHEELENCODER_MSG 0x0F
|
||||
#define LOG_ERROR_MSG 0x13
|
||||
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
|
|
Loading…
Reference in New Issue