ardupilot/ArduSub/control_manual.cpp

39 lines
1.3 KiB
C++

#include "Sub.h"
// manual_init - initialise manual controller
bool Sub::manual_init()
{
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
// attitude hold inputs become thrust inputs in manual mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
set_neutral_controls();
return true;
}
// manual_run - runs the manual (passthrough) controller
// should be called at 100hz or more
void Sub::manual_run()
{
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
return;
}
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
motors.set_roll(channel_roll->norm_input());
motors.set_pitch(channel_pitch->norm_input());
motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P);
motors.set_throttle(channel_throttle->norm_input());
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
float dt = ((float)(micros() - last_control_mode_update_us)) / 1e6;
motors.limit_demand_slew_rate(g.manual_slew_rate, dt);
}