mirror of https://github.com/ArduPilot/ardupilot
AP_ServoTelem: added active mask
and fixed typo in logging
This commit is contained in:
parent
bf5555ccd3
commit
445c03c69c
|
@ -61,6 +61,7 @@ void AP_Servo_Telem::update_telem_data(const uint8_t servo_index, const Telemetr
|
||||||
if (servo_index >= ARRAY_SIZE(_telem_data) || (new_data.valid_types == 0)) {
|
if (servo_index >= ARRAY_SIZE(_telem_data) || (new_data.valid_types == 0)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
active_mask |= 1U << servo_index;
|
||||||
|
|
||||||
volatile TelemetryData &telemdata = _telem_data[servo_index];
|
volatile TelemetryData &telemdata = _telem_data[servo_index];
|
||||||
|
|
||||||
|
@ -112,7 +113,7 @@ void AP_Servo_Telem::write_log()
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
|
|
||||||
// Check logging is available and enabled
|
// Check logging is available and enabled
|
||||||
if ((logger == nullptr) || !logger->logging_enabled()) {
|
if ((logger == nullptr) || !logger->logging_enabled() || active_mask == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -138,7 +139,7 @@ void AP_Servo_Telem::write_log()
|
||||||
force : telemdata.present(TelemetryData::Types::FORCE) ? telemdata.force : AP::logger().quiet_nanf(),
|
force : telemdata.present(TelemetryData::Types::FORCE) ? telemdata.force : AP::logger().quiet_nanf(),
|
||||||
speed : telemdata.present(TelemetryData::Types::SPEED) ? telemdata.speed : AP::logger().quiet_nanf(),
|
speed : telemdata.present(TelemetryData::Types::SPEED) ? telemdata.speed : AP::logger().quiet_nanf(),
|
||||||
power_pct : telemdata.duty_cycle,
|
power_pct : telemdata.duty_cycle,
|
||||||
pos_cmd : telemdata.present(TelemetryData::Types::MEASURED_POSITION) ? telemdata.command_position : AP::logger().quiet_nanf(),
|
pos_cmd : telemdata.present(TelemetryData::Types::COMMANDED_POSITION) ? telemdata.command_position : AP::logger().quiet_nanf(),
|
||||||
voltage : telemdata.present(TelemetryData::Types::VOLTAGE) ? telemdata.voltage : AP::logger().quiet_nanf(),
|
voltage : telemdata.present(TelemetryData::Types::VOLTAGE) ? telemdata.voltage : AP::logger().quiet_nanf(),
|
||||||
current : telemdata.present(TelemetryData::Types::CURRENT) ? telemdata.current : AP::logger().quiet_nanf(),
|
current : telemdata.present(TelemetryData::Types::CURRENT) ? telemdata.current : AP::logger().quiet_nanf(),
|
||||||
mot_temp : telemdata.present(TelemetryData::Types::MOTOR_TEMP) ? telemdata.motor_temperature_cdeg * 0.01 : AP::logger().quiet_nanf(),
|
mot_temp : telemdata.present(TelemetryData::Types::MOTOR_TEMP) ? telemdata.motor_temperature_cdeg * 0.01 : AP::logger().quiet_nanf(),
|
||||||
|
|
|
@ -80,5 +80,7 @@ private:
|
||||||
uint32_t _last_telem_log_ms[SERVO_TELEM_MAX_SERVOS];
|
uint32_t _last_telem_log_ms[SERVO_TELEM_MAX_SERVOS];
|
||||||
|
|
||||||
static AP_Servo_Telem *_singleton;
|
static AP_Servo_Telem *_singleton;
|
||||||
|
|
||||||
|
uint32_t active_mask;
|
||||||
};
|
};
|
||||||
#endif // AP_SERVO_TELEM_ENABLED
|
#endif // AP_SERVO_TELEM_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue