ardupilot/Blimp/mode_manual.cpp

14 lines
428 B
C++
Raw Normal View History

#include "Blimp.h"
/*
2021-06-17 04:03:49 -03:00
* Init and run calls for manual flight mode
*/
2021-06-17 04:03:49 -03:00
// Runs the main manual controller
void ModeManual::run()
{
motors->right_out = channel_right->get_control_in() / float(RC_SCALE);
motors->front_out = channel_front->get_control_in() / float(RC_SCALE);
motors->yaw_out = channel_yaw->get_control_in() / float(RC_SCALE);
motors->down_out = channel_down->get_control_in() / float(RC_SCALE);
}