mirror of https://github.com/ArduPilot/ardupilot
Sub: add airspeed sensors
This commit is contained in:
parent
0e41b821e8
commit
d197ec4072
|
@ -78,6 +78,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
|
||||
#endif
|
||||
SCHED_TASK(read_airspeed, 10, 100),
|
||||
};
|
||||
|
||||
void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
|
|
|
@ -632,13 +632,18 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPINFO(scripting, "SCR_", 18, ParametersG2, AP_Scripting),
|
||||
#endif
|
||||
|
||||
// @Group: ARSPD
|
||||
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
|
||||
AP_SUBGROUPINFO(airspeed, "ARSPD", 19, ParametersG2, AP_Airspeed),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
/*
|
||||
constructor for g2 object
|
||||
*/
|
||||
ParametersG2::ParametersG2()
|
||||
ParametersG2::ParametersG2():
|
||||
airspeed()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
|
|
@ -335,6 +335,9 @@ public:
|
|||
AP_Scripting scripting;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
|
||||
// Airspeed
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -610,6 +610,7 @@ private:
|
|||
void auto_spline_start(const Location& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location& next_destination);
|
||||
void log_init(void);
|
||||
void accel_cal_update(void);
|
||||
void read_airspeed();
|
||||
|
||||
void failsafe_leak_check();
|
||||
void failsafe_internal_pressure_check();
|
||||
|
|
|
@ -107,3 +107,11 @@ void Sub::accel_cal_update()
|
|||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
ask airspeed sensor for a new value, duplicated from plane
|
||||
*/
|
||||
void Sub::read_airspeed()
|
||||
{
|
||||
g2.airspeed.update(should_log(MASK_LOG_IMU));
|
||||
}
|
||||
|
|
|
@ -165,6 +165,8 @@ void Sub::init_ardupilot()
|
|||
g2.scripting.init();
|
||||
#endif // ENABLE_SCRIPTING
|
||||
|
||||
g2.airspeed.init();
|
||||
|
||||
// we don't want writes to the serial port to cause us to pause
|
||||
// mid-flight, so set the serial ports non-blocking once we are
|
||||
// ready to fly
|
||||
|
|
Loading…
Reference in New Issue