mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: 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
fbb28a0c3a
commit
e29b6c3036
|
@ -727,7 +727,7 @@ void Copter::one_hz_loop()
|
||||||
}
|
}
|
||||||
|
|
||||||
// update assigned functions and enable auxiliary servos
|
// update assigned functions and enable auxiliary servos
|
||||||
SRV_Channels::enable_aux_servos();
|
AP::srv().enable_aux_servos();
|
||||||
|
|
||||||
#if HAL_LOGGING_ENABLED
|
#if HAL_LOGGING_ENABLED
|
||||||
// log terrain data
|
// log terrain data
|
||||||
|
|
|
@ -148,7 +148,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||||
// pass through throttle to motors
|
// pass through throttle to motors
|
||||||
SRV_Channels::cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
|
|
||||||
// read some compass values
|
// read some compass values
|
||||||
compass.read();
|
compass.read();
|
||||||
|
|
|
@ -97,7 +97,7 @@ void Copter::esc_calibration_passthrough()
|
||||||
// pass through to motors
|
// pass through to motors
|
||||||
SRV_Channels::cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
}
|
}
|
||||||
#endif // FRAME_CONFIG != HELI_FRAME
|
#endif // FRAME_CONFIG != HELI_FRAME
|
||||||
}
|
}
|
||||||
|
@ -114,14 +114,14 @@ void Copter::esc_calibration_auto()
|
||||||
// raise throttle to maximum
|
// raise throttle to maximum
|
||||||
SRV_Channels::cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
|
|
||||||
// delay for 5 seconds while outputting pulses
|
// delay for 5 seconds while outputting pulses
|
||||||
uint32_t tstart = millis();
|
uint32_t tstart = millis();
|
||||||
while (millis() - tstart < 5000) {
|
while (millis() - tstart < 5000) {
|
||||||
SRV_Channels::cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
esc_calibration_notify();
|
esc_calibration_notify();
|
||||||
hal.scheduler->delay(3);
|
hal.scheduler->delay(3);
|
||||||
}
|
}
|
||||||
|
@ -130,7 +130,7 @@ void Copter::esc_calibration_auto()
|
||||||
while(1) {
|
while(1) {
|
||||||
SRV_Channels::cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
esc_calibration_notify();
|
esc_calibration_notify();
|
||||||
hal.scheduler->delay(3);
|
hal.scheduler->delay(3);
|
||||||
}
|
}
|
||||||
|
|
|
@ -181,7 +181,7 @@ void Copter::motors_output()
|
||||||
}
|
}
|
||||||
|
|
||||||
// push all channels
|
// push all channels
|
||||||
SRV_Channels::push();
|
AP::srv().push();
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for pilot stick input to trigger lost vehicle alarm
|
// check for pilot stick input to trigger lost vehicle alarm
|
||||||
|
|
|
@ -45,7 +45,7 @@ void Copter::init_rc_out()
|
||||||
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
||||||
|
|
||||||
// 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();
|
||||||
|
|
||||||
// update rate must be set after motors->init() to allow for motor mapping
|
// update rate must be set after motors->init() to allow for motor mapping
|
||||||
motors->set_update_rate(g.rc_speed);
|
motors->set_update_rate(g.rc_speed);
|
||||||
|
|
Loading…
Reference in New Issue