mirror of https://github.com/ArduPilot/ardupilot
Plane: add support for RCn_OPTION (servorelay,camera)
Closes #7071 Closes #7666
This commit is contained in:
parent
450052aa80
commit
901664ce09
|
@ -90,6 +90,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
#endif
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50),
|
||||
SCHED_TASK(avoidance_adsb_update, 10, 100),
|
||||
SCHED_TASK(read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_Button, &plane.g2.button, update, 5, 100),
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &plane.g2.stats, update, 1, 100),
|
||||
|
@ -130,6 +131,11 @@ void Plane::update_soft_armed()
|
|||
DataFlash.set_vehicle_armed(hal.util->get_soft_armed());
|
||||
}
|
||||
|
||||
void Plane::read_aux_all()
|
||||
{
|
||||
plane.g2.rc_channels.read_aux_all();
|
||||
}
|
||||
|
||||
// update AHRS system
|
||||
void Plane::ahrs_update()
|
||||
{
|
||||
|
|
|
@ -1033,6 +1033,8 @@ private:
|
|||
void update_soaring();
|
||||
#endif
|
||||
|
||||
void read_aux_all();
|
||||
|
||||
// support for AP_Avoidance custom flight mode, AVOID_ADSB
|
||||
bool avoid_adsb_init(bool ignore_checks);
|
||||
void avoid_adsb_run();
|
||||
|
|
|
@ -15,3 +15,14 @@ int8_t RC_Channels_Plane::flight_mode_channel_number() const
|
|||
{
|
||||
return plane.g.flight_mode_channel.get();
|
||||
}
|
||||
|
||||
bool RC_Channels_Plane::has_valid_input() const
|
||||
{
|
||||
if (plane.failsafe.rc_failsafe) {
|
||||
return false;
|
||||
}
|
||||
if (plane.failsafe.throttle_counter != 0) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -25,6 +25,8 @@ public:
|
|||
return &obj_channels[chan];
|
||||
}
|
||||
|
||||
bool has_valid_input() const override;
|
||||
|
||||
protected:
|
||||
|
||||
// note that these callbacks are not presently used on Plane:
|
||||
|
|
Loading…
Reference in New Issue