ardupilot/ArduSub/mode_manual.cpp

36 lines
1.2 KiB
C++
Raw Normal View History

2016-06-26 01:07:27 -03:00
#include "Sub.h"
2023-04-03 09:11:21 -03:00
bool ModeManual::init(bool ignore_checks) {
2016-06-26 01:07:27 -03:00
// set target altitude to zero for reporting
2023-04-03 09:11:21 -03:00
position_control->set_pos_target_z_cm(0);
2016-06-26 01:07:27 -03:00
// attitude hold inputs become thrust inputs in manual mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
2023-04-03 09:11:21 -03:00
sub.set_neutral_controls();
2016-06-26 01:07:27 -03:00
return true;
}
// manual_run - runs the manual (passthrough) controller
// should be called at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeManual::run()
2016-06-26 01:07:27 -03:00
{
// if not armed set throttle to zero and exit immediately
2023-04-03 09:11:21 -03:00
if (!sub.motors.armed()) {
sub.motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
2016-06-26 01:07:27 -03:00
return;
}
2023-04-03 09:11:21 -03:00
sub.motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
2016-06-26 01:07:27 -03:00
2023-04-03 09:11:21 -03:00
sub.motors.set_roll(channel_roll->norm_input());
sub.motors.set_pitch(channel_pitch->norm_input());
sub.motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P);
sub.motors.set_throttle(channel_throttle->norm_input());
sub.motors.set_forward(channel_forward->norm_input());
sub.motors.set_lateral(channel_lateral->norm_input());
2016-06-26 01:07:27 -03:00
}