Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: Set the flight mode at startup to the flight SW. #13330

Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 18 additions & 4 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,6 @@ void Copter::init_ardupilot()
// init winch and wheel encoder
winch_init();

// initialise notify system
notify.init();
notify_flight_mode();

// initialise battery monitor
battery.init();

Expand Down Expand Up @@ -187,6 +183,24 @@ void Copter::init_ardupilot()
ins.set_hil_mode();
#endif

// Setting the flight mode of the flight mode switch
int8_t flightCH = copter.g.flight_mode_chan.get();
uint16_t ch_in = rc().channel(flightCH - 1)->get_radio_in();
int8_t position = 0;
if (ch_in < 1231) position = 0;
else if (ch_in < 1361) position = 1;
else if (ch_in < 1491) position = 2;
else if (ch_in < 1621) position = 3;
else if (ch_in < 1750) position = 4;
else position = 5;

control_mode = (enum Mode::Number)flight_modes[position].get();
flightmode = mode_from_mode_num(control_mode);

// initialise notify system
notify.init();
notify_flight_mode();

// read Baro pressure at ground
//-----------------------------
barometer.set_log_baro_bit(MASK_LOG_IMU);
Expand Down