Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/mode_manual.cpp
9418 views
1
#include "Sub.h"
2
3
4
bool ModeManual::init(bool ignore_checks) {
5
// set target altitude to zero for reporting
6
position_control->set_pos_desired_U_cm(0);
7
8
// attitude hold inputs become thrust inputs in manual mode
9
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
10
sub.set_neutral_controls();
11
12
return true;
13
}
14
15
// manual_run - runs the manual (passthrough) controller
16
// should be called at 100hz or more
17
void ModeManual::run()
18
{
19
// if not armed set throttle to zero and exit immediately
20
if (!sub.motors.armed()) {
21
sub.motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
22
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
23
attitude_control->relax_attitude_controllers();
24
return;
25
}
26
27
sub.motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
28
29
sub.motors.set_roll(channel_roll->norm_input());
30
sub.motors.set_pitch(channel_pitch->norm_input());
31
sub.motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P);
32
sub.motors.set_throttle((channel_throttle->norm_input() + 1.0f) / 2.0f);
33
sub.motors.set_forward(channel_forward->norm_input());
34
sub.motors.set_lateral(channel_lateral->norm_input());
35
}
36
37