ardupilot/Blimp/mode_manual.cpp

17 lines
345 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()
{
2023-07-27 02:03:08 -03:00
Vector3f pilot;
float pilot_yaw;
get_pilot_input(pilot, pilot_yaw);
motors->right_out = pilot.y;
motors->front_out = pilot.x;
motors->yaw_out = pilot_yaw;
motors->down_out = pilot.z;
}