@ -93,6 +93,9 @@ void Tracker::one_second_loop()
// sync MAVLink system ID
mavlink_system.sysid = g.sysid_this_mav;
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
// updated armed/disarmed status LEDs
update_armed_disarmed();
@ -7,6 +7,9 @@
// init_servos - initialises the servos
void Tracker::init_servos()
{
SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);
SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);