mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Plane: make it possible to change control channel ordering without reboot
this makes configuration a bit easier
This commit is contained in:
parent
27bc0cdc2c
commit
4c9bc30f58
@ -958,6 +958,9 @@ static void one_second_loop()
|
|||||||
|
|
||||||
// send a heartbeat
|
// send a heartbeat
|
||||||
gcs_send_message(MSG_HEARTBEAT);
|
gcs_send_message(MSG_HEARTBEAT);
|
||||||
|
|
||||||
|
// make it possible to change control channel ordering at runtime
|
||||||
|
set_control_channels();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void update_GPS(void)
|
static void update_GPS(void)
|
||||||
|
@ -4,7 +4,20 @@
|
|||||||
// ----------------------------------------------------------------------------
|
// ----------------------------------------------------------------------------
|
||||||
static uint8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
static uint8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||||
|
|
||||||
|
/*
|
||||||
|
allow for runtime change of control channel ordering
|
||||||
|
*/
|
||||||
|
static void set_control_channels(void)
|
||||||
|
{
|
||||||
|
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
||||||
|
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
||||||
|
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
||||||
|
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
initialise RC input channels
|
||||||
|
*/
|
||||||
static void init_rc_in()
|
static void init_rc_in()
|
||||||
{
|
{
|
||||||
// set rc channel ranges
|
// set rc channel ranges
|
||||||
@ -34,6 +47,9 @@ static void init_rc_in()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
initialise RC output channels
|
||||||
|
*/
|
||||||
static void init_rc_out()
|
static void init_rc_out()
|
||||||
{
|
{
|
||||||
channel_roll->enable_out();
|
channel_roll->enable_out();
|
||||||
|
@ -110,11 +110,7 @@ static void init_ardupilot()
|
|||||||
//
|
//
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
|
||||||
// setup channel mappings. Changing these requires a reboot
|
set_control_channels();
|
||||||
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
|
||||||
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
|
||||||
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
|
||||||
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
|
||||||
|
|
||||||
// reset the uartA baud rate after parameter load
|
// reset the uartA baud rate after parameter load
|
||||||
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
|
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
|
||||||
|
Loading…
Reference in New Issue
Block a user