mirror of https://github.com/ArduPilot/ardupilot
Rover: 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
52e2a162c9
commit
ccd12e3e12
|
@ -435,7 +435,7 @@ void Rover::one_second_loop(void)
|
||||||
set_control_channels();
|
set_control_channels();
|
||||||
|
|
||||||
// cope with changes to aux functions
|
// cope with changes to aux functions
|
||||||
SRV_Channels::enable_aux_servos();
|
AP::srv().enable_aux_servos();
|
||||||
|
|
||||||
// update notify flags
|
// update notify flags
|
||||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||||
|
|
|
@ -70,7 +70,7 @@ void Rover::init_ardupilot()
|
||||||
|
|
||||||
init_rc_in(); // sets up rc channels deadzone
|
init_rc_in(); // sets up rc channels deadzone
|
||||||
g2.motors.init(get_frame_type()); // init motors including setting servo out channels ranges
|
g2.motors.init(get_frame_type()); // init motors including setting servo out channels ranges
|
||||||
SRV_Channels::enable_aux_servos();
|
AP::srv().enable_aux_servos();
|
||||||
|
|
||||||
// init wheel encoders
|
// init wheel encoders
|
||||||
g2.wheel_encoder.init();
|
g2.wheel_encoder.init();
|
||||||
|
|
Loading…
Reference in New Issue