mirror of https://github.com/ArduPilot/ardupilot
23 lines
653 B
C++
23 lines
653 B
C++
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#include "Tracker.h"
|
|
|
|
/*
|
|
* control_manual.pde - manual control mode
|
|
*/
|
|
|
|
/*
|
|
* update_manual - runs the manual controller
|
|
* called at 50hz while control_mode is 'MANUAL'
|
|
*/
|
|
void Tracker::update_manual(void)
|
|
{
|
|
// copy yaw and pitch input to output
|
|
channel_yaw.radio_out = constrain_int16(channel_yaw.radio_in, channel_yaw.radio_min, channel_yaw.radio_max);
|
|
channel_pitch.radio_out = constrain_int16(channel_pitch.radio_in, channel_pitch.radio_min, channel_pitch.radio_max);
|
|
|
|
// send output to servos
|
|
channel_yaw.output();
|
|
channel_pitch.output();
|
|
}
|