AP_Logger: log default param values
This commit is contained in:
parent
5b290920a7
commit
63e03622d4
@ -865,7 +865,7 @@ void AP_Logger::Write_Mode(uint8_t mode, const ModeReason reason)
|
||||
|
||||
void AP_Logger::Write_Parameter(const char *name, float value)
|
||||
{
|
||||
FOR_EACH_BACKEND(Write_Parameter(name, value));
|
||||
FOR_EACH_BACKEND(Write_Parameter(name, value, quiet_nanf()));
|
||||
}
|
||||
|
||||
void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
|
||||
|
@ -128,10 +128,11 @@ public:
|
||||
bool Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
bool Write_Mode(uint8_t mode, const ModeReason reason);
|
||||
bool Write_Parameter(const char *name, float value);
|
||||
bool Write_Parameter(const char *name, float value, float default_val);
|
||||
bool Write_Parameter(const AP_Param *ap,
|
||||
const AP_Param::ParamToken &token,
|
||||
enum ap_var_type type);
|
||||
enum ap_var_type type,
|
||||
float default_val);
|
||||
bool Write_VER();
|
||||
|
||||
uint32_t num_dropped(void) const {
|
||||
|
@ -103,13 +103,14 @@ bool AP_Logger_Backend::Write_Format_Units(const struct LogStructure *s)
|
||||
/*
|
||||
write a parameter to the log
|
||||
*/
|
||||
bool AP_Logger_Backend::Write_Parameter(const char *name, float value)
|
||||
bool AP_Logger_Backend::Write_Parameter(const char *name, float value, float default_val)
|
||||
{
|
||||
struct log_Parameter pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
name : {},
|
||||
value : value
|
||||
value : value,
|
||||
default_value : default_val
|
||||
};
|
||||
strncpy_noterm(pkt.name, name, sizeof(pkt.name));
|
||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -120,11 +121,12 @@ bool AP_Logger_Backend::Write_Parameter(const char *name, float value)
|
||||
*/
|
||||
bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap,
|
||||
const AP_Param::ParamToken &token,
|
||||
enum ap_var_type type)
|
||||
enum ap_var_type type,
|
||||
float default_val)
|
||||
{
|
||||
char name[16];
|
||||
ap->copy_name_token(token, &name[0], sizeof(name), true);
|
||||
return Write_Parameter(name, ap->cast_to_float(type));
|
||||
return Write_Parameter(name, ap->cast_to_float(type), default_val);
|
||||
}
|
||||
|
||||
// Write an RCIN packet
|
||||
|
@ -205,6 +205,7 @@ struct PACKED log_Parameter {
|
||||
uint64_t time_us;
|
||||
char name[16];
|
||||
float value;
|
||||
float default_value;
|
||||
};
|
||||
|
||||
struct PACKED log_DSF {
|
||||
@ -920,6 +921,7 @@ struct PACKED log_VER {
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Name: parameter name
|
||||
// @Field: Value: parameter value
|
||||
// @Field: Default: default parameter value for this board and config
|
||||
|
||||
// @LoggerMessage: PIDR,PIDP,PIDY,PIDA,PIDS,PIDN,PIDE
|
||||
// @Description: Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Altitude/Steering
|
||||
@ -1213,7 +1215,7 @@ struct PACKED log_VER {
|
||||
{ LOG_MULT_MSG, sizeof(log_Format_Multiplier), \
|
||||
"MULT", "Qbd", "TimeUS,Id,Mult", "s--","F--" }, \
|
||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||
"PARM", "QNf", "TimeUS,Name,Value", "s--", "F--" }, \
|
||||
"PARM", "QNff", "TimeUS,Name,Value,Default", "s---", "F---" }, \
|
||||
LOG_STRUCTURE_FROM_GPS \
|
||||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||
"MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \
|
||||
|
@ -50,7 +50,8 @@ void LoggerMessageWriter_DFLogStart::reset()
|
||||
_next_unit_to_send = 0;
|
||||
_next_multiplier_to_send = 0;
|
||||
_next_format_unit_to_send = 0;
|
||||
ap = AP_Param::first(&token, &type);
|
||||
param_default = AP::logger().quiet_nanf();
|
||||
ap = AP_Param::first(&token, &type, ¶m_default);
|
||||
}
|
||||
|
||||
bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const
|
||||
@ -87,10 +88,11 @@ void LoggerMessageWriter_DFLogStart::process()
|
||||
|
||||
case Stage::PARMS:
|
||||
while (ap) {
|
||||
if (!_logger_backend->Write_Parameter(ap, token, type)) {
|
||||
if (!_logger_backend->Write_Parameter(ap, token, type, param_default)) {
|
||||
return;
|
||||
}
|
||||
ap = AP_Param::next_scalar(&token, &type);
|
||||
param_default = AP::logger().quiet_nanf();
|
||||
ap = AP_Param::next_scalar(&token, &type, ¶m_default);
|
||||
}
|
||||
|
||||
_params_done = true;
|
||||
|
@ -140,6 +140,7 @@ private:
|
||||
|
||||
AP_Param::ParamToken token;
|
||||
AP_Param *ap;
|
||||
float param_default;
|
||||
enum ap_var_type type;
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user