mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Plane: Don't initilize motors with a trim value
This commit is contained in:
parent
0d56c56610
commit
33a0425286
@ -247,15 +247,6 @@ void Plane::afs_fs_check(void)
|
||||
afs.check(failsafe.last_heartbeat_ms, geofence_breached(), failsafe.AFS_last_valid_rc_ms);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
update aux servo mappings
|
||||
*/
|
||||
void Plane::update_aux(void)
|
||||
{
|
||||
SRV_Channels::enable_aux_servos();
|
||||
}
|
||||
|
||||
void Plane::one_second_loop()
|
||||
{
|
||||
// send a heartbeat
|
||||
@ -280,7 +271,7 @@ void Plane::one_second_loop()
|
||||
// sync MAVLink system ID
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
update_aux();
|
||||
SRV_Channels::enable_aux_servos();
|
||||
|
||||
// update notify flags
|
||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||
|
@ -965,7 +965,6 @@ private:
|
||||
void servos_twin_engine_mix();
|
||||
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
|
||||
bool allow_reverse_thrust(void);
|
||||
void update_aux();
|
||||
void update_is_flying_5Hz(void);
|
||||
void crash_detection_update(void);
|
||||
bool in_preLaunch_flight_stage(void);
|
||||
|
@ -90,18 +90,15 @@ void Plane::init_rc_out_main()
|
||||
*/
|
||||
void Plane::init_rc_out_aux()
|
||||
{
|
||||
update_aux();
|
||||
SRV_Channels::enable_aux_servos();
|
||||
|
||||
SRV_Channels::cork();
|
||||
|
||||
// Initialization of servo outputs
|
||||
SRV_Channels::output_trim_all();
|
||||
|
||||
servos_output();
|
||||
|
||||
// setup PWM values to send if the FMU firmware dies
|
||||
SRV_Channels::setup_failsafe_trim_all();
|
||||
// allows any VTOL motors to shut off
|
||||
SRV_Channels::setup_failsafe_trim_all_non_motors();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -227,10 +227,6 @@ void Plane::dspoiler_update(void)
|
||||
*/
|
||||
void Plane::set_servos_idle(void)
|
||||
{
|
||||
if (auto_state.idle_wiggle_stage == 0) {
|
||||
SRV_Channels::output_trim_all();
|
||||
return;
|
||||
}
|
||||
int16_t servo_value = 0;
|
||||
// move over full range for 2 seconds
|
||||
auto_state.idle_wiggle_stage += 2;
|
||||
|
Loading…
Reference in New Issue
Block a user