mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
AP_InertialSensor: added get_temperature() interface
this will allow logging of individual temperature sensors
This commit is contained in:
parent
9468a59204
commit
23272e4013
@ -160,6 +160,10 @@ public:
|
||||
const Vector3f &get_accel_scale(uint8_t i) const { return _accel_scale[i]; }
|
||||
const Vector3f &get_accel_scale(void) const { return get_accel_scale(_primary_accel); }
|
||||
|
||||
// return the temperature if supported. Zero is returned if no
|
||||
// temperature is available
|
||||
float get_temperature(uint8_t instance) const { return _temperature[instance]; }
|
||||
|
||||
/* get_delta_time returns the time period in seconds
|
||||
* overwhich the sensor data was collected
|
||||
*/
|
||||
@ -261,6 +265,9 @@ private:
|
||||
AP_Vector3f _accel_offset[INS_MAX_INSTANCES];
|
||||
AP_Vector3f _gyro_offset[INS_MAX_INSTANCES];
|
||||
|
||||
// temperatures for an instance if available
|
||||
float _temperature[INS_MAX_INSTANCES];
|
||||
|
||||
// filtering frequency (0 means default)
|
||||
AP_Int8 _accel_filter_cutoff;
|
||||
AP_Int8 _gyro_filter_cutoff;
|
||||
|
@ -95,3 +95,11 @@ uint16_t AP_InertialSensor_Backend::get_sample_rate_hz(void) const
|
||||
// enum can be directly cast to Hz
|
||||
return (uint16_t)_imu._sample_rate;
|
||||
}
|
||||
|
||||
/*
|
||||
publish a temperature value for an instance
|
||||
*/
|
||||
void AP_InertialSensor_Backend::_publish_temperature(uint8_t instance, float temperature)
|
||||
{
|
||||
_imu._temperature[instance] = temperature;
|
||||
}
|
||||
|
@ -73,6 +73,9 @@ protected:
|
||||
// rotate accel vector, scale, offset and publish
|
||||
void _publish_accel(uint8_t instance, const Vector3f &accel, bool rotate_and_correct = true);
|
||||
|
||||
// publish a temperature value
|
||||
void _publish_temperature(uint8_t instance, float temperature);
|
||||
|
||||
// set accelerometer error_count
|
||||
void _set_accel_error_count(uint8_t instance, uint32_t error_count);
|
||||
|
||||
|
@ -270,6 +270,9 @@ void AP_InertialSensor_PX4::_new_accel_sample(uint8_t i, accel_report &accel_rep
|
||||
// report error count
|
||||
_set_accel_error_count(frontend_instance, accel_report.error_count);
|
||||
|
||||
// publish a temperature (for logging purposed only)
|
||||
_publish_temperature(frontend_instance, accel_report.temperature);
|
||||
|
||||
#ifdef AP_INERTIALSENSOR_PX4_DEBUG
|
||||
_accel_dt_max[i] = max(_accel_dt_max[i],dt);
|
||||
|
||||
@ -377,12 +380,26 @@ void AP_InertialSensor_PX4::_get_sample()
|
||||
_last_get_sample_timestamp = hal.scheduler->micros64();
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_PX4::_get_accel_sample(uint8_t i, struct accel_report &accel_report) {
|
||||
return i<_num_accel_instances && _accel_fd[i] != -1 && ::read(_accel_fd[i], &accel_report, sizeof(accel_report)) == sizeof(accel_report) && accel_report.timestamp != _last_accel_timestamp[i];
|
||||
bool AP_InertialSensor_PX4::_get_accel_sample(uint8_t i, struct accel_report &accel_report)
|
||||
{
|
||||
if (i<_num_accel_instances &&
|
||||
_accel_fd[i] != -1 &&
|
||||
::read(_accel_fd[i], &accel_report, sizeof(accel_report)) == sizeof(accel_report) &&
|
||||
accel_report.timestamp != _last_accel_timestamp[i]) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_PX4::_get_gyro_sample(uint8_t i, struct gyro_report &gyro_report) {
|
||||
return i<_num_gyro_instances && _gyro_fd[i] != -1 && ::read(_gyro_fd[i], &gyro_report, sizeof(gyro_report)) == sizeof(gyro_report) && gyro_report.timestamp != _last_gyro_timestamp[i];
|
||||
bool AP_InertialSensor_PX4::_get_gyro_sample(uint8_t i, struct gyro_report &gyro_report)
|
||||
{
|
||||
if (i<_num_gyro_instances &&
|
||||
_gyro_fd[i] != -1 &&
|
||||
::read(_gyro_fd[i], &gyro_report, sizeof(gyro_report)) == sizeof(gyro_report) &&
|
||||
gyro_report.timestamp != _last_gyro_timestamp[i]) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_PX4::gyro_sample_available(void)
|
||||
|
Loading…
Reference in New Issue
Block a user