Browse Source

Copter: enable temperature calibration library

master
Andrew Tridgell 8 years ago
parent
commit
15166eff2e
  1. 1
      ArduCopter/ArduCopter.cpp
  2. 3
      ArduCopter/Copter.h
  3. 6
      ArduCopter/Parameters.cpp
  4. 3
      ArduCopter/Parameters.h
  5. 5
      ArduCopter/sensors.cpp

1
ArduCopter/ArduCopter.cpp

@ -133,6 +133,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { @@ -133,6 +133,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(rpm_update, 10, 200),
SCHED_TASK(compass_cal_update, 100, 100),
SCHED_TASK(accel_cal_update, 10, 100),
SCHED_TASK(temp_cal_update, 10, 100),
#if ADSB_ENABLED == ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100),
#endif

3
ArduCopter/Copter.h

@ -97,6 +97,7 @@ @@ -97,6 +97,7 @@
#include <AP_SmartRTL/AP_SmartRTL.h>
#include <AP_WheelEncoder/AP_WheelEncoder.h>
#include <AP_Winch/AP_Winch.h>
#include <AP_TempCalibration/AP_TempCalibration.h>
// Configuration
#include "defines.h"
@ -973,6 +974,8 @@ private: @@ -973,6 +974,8 @@ private:
Mode *mode_from_mode_num(const uint8_t mode);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
void temp_cal_update(void);
public:
void mavlink_delay_cb(); // GCS_Mavlink.cpp
void failsafe_check(); // failsafe.cpp

6
ArduCopter/Parameters.cpp

@ -930,7 +930,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -930,7 +930,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(visual_odom, "VISO", 18, ParametersG2, AP_VisualOdom),
#endif
// ID 19 reserved for TCAL (PR pending)
// @Group: TCAL
// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp
AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration),
// ID 20 reserved for TX_TYPE (PR pending)
// @Group: SRTL_
@ -979,6 +982,7 @@ ParametersG2::ParametersG2(void) @@ -979,6 +982,7 @@ ParametersG2::ParametersG2(void)
,afs(copter.mission, copter.barometer, copter.gps, copter.rcmap)
#endif
,smart_rtl(copter.ahrs)
,temp_calibration(copter.barometer, copter.ins)
{
AP_Param::setup_object_defaults(this, var_info);
}

3
ArduCopter/Parameters.h

@ -561,6 +561,9 @@ public: @@ -561,6 +561,9 @@ public:
// Land alt final stage
AP_Int16 land_alt_low;
// temperature calibration handling
AP_TempCalibration temp_calibration;
};
extern const AP_Param::Info var_info[];

5
ArduCopter/sensors.cpp

@ -552,3 +552,8 @@ void Copter::winch_update() @@ -552,3 +552,8 @@ void Copter::winch_update()
g2.wheel_encoder.update();
g2.winch.update();
}
void Copter::temp_cal_update(void)
{
g2.temp_calibration.update();
}

Loading…
Cancel
Save