mirror of https://github.com/ArduPilot/ardupilot
Blimp: create and use a singleton for SRV_Channels
avoid creation of static pointers to objects held within SRV_Channels
This commit is contained in:
parent
a8b07a854f
commit
52e2a162c9
|
@ -210,7 +210,7 @@ void Blimp::one_hz_loop()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// update assigned functions and enable auxiliary servos
|
// update assigned functions and enable auxiliary servos
|
||||||
SRV_Channels::enable_aux_servos();
|
AP::srv().enable_aux_servos();
|
||||||
|
|
||||||
AP_Notify::flags.flying = !ap.land_complete;
|
AP_Notify::flags.flying = !ap.land_complete;
|
||||||
|
|
||||||
|
|
|
@ -88,5 +88,5 @@ void Blimp::motors_output()
|
||||||
motors->output();
|
motors->output();
|
||||||
|
|
||||||
// push all channels
|
// push all channels
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
}
|
}
|
|
@ -38,7 +38,7 @@ void Blimp::init_rc_in()
|
||||||
void Blimp::init_rc_out()
|
void Blimp::init_rc_out()
|
||||||
{
|
{
|
||||||
// enable aux servos to cope with multiple output channels per motor
|
// enable aux servos to cope with multiple output channels per motor
|
||||||
SRV_Channels::enable_aux_servos();
|
AP::srv().enable_aux_servos();
|
||||||
|
|
||||||
// refresh auxiliary channel to function map
|
// refresh auxiliary channel to function map
|
||||||
SRV_Channels::update_aux_servo_function();
|
SRV_Channels::update_aux_servo_function();
|
||||||
|
|
Loading…
Reference in New Issue