ardupilot/AntennaTracker/mode_manual.cpp

20 lines
579 B
C++
Raw Normal View History

#include "Tracker.h"
2015-04-17 21:45:26 -03:00
/*
* Manual control mode
2015-04-17 21:45:26 -03:00
*/
/*
* update_manual - runs the manual controller
* called at 50hz while control mode is 'MANUAL'
2015-04-17 21:45:26 -03:00
*/
void ModeManual::update()
2015-04-17 21:45:26 -03:00
{
// copy yaw and pitch input to output
SRV_Channels::set_output_pwm(SRV_Channel::k_tracker_yaw, RC_Channels::rc_channel(CH_YAW)->get_radio_in());
SRV_Channels::constrain_pwm(SRV_Channel::k_tracker_yaw);
2019-06-13 14:16:29 -03:00
SRV_Channels::set_output_pwm(SRV_Channel::k_tracker_pitch, RC_Channels::rc_channel(CH_PITCH)->get_radio_in());
SRV_Channels::constrain_pwm(SRV_Channel::k_tracker_pitch);
2015-04-17 21:45:26 -03:00
}