#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; } extern mavlink_rov_state_monitoring_t rov_message; void Sub::manual_run() { // if not armed set throttle to zero and exit immediately if (!motors.armed()) { 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(); PressLevel_f =5.0; PressLevel = no; return; } motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); motors.set_roll(channel_lateral->norm_input());//(channel_roll->norm_input());//左右移动改为roll motors.set_pitch((0.5-channel_throttle->norm_input())*2);//(channel_pitch->norm_input());//上升下潜改为pitch motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P); motors.set_forward(channel_forward->norm_input()); motors.set_lateral(0.0);//(channel_lateral->norm_input()); motors.set_throttle(1.0-(float)PressLevel_f*0.1);//0-0.5下压 static int j = 0; j++; if(j>800) { //gcs().send_text(MAV_SEVERITY_INFO, " PressLevel_f %f \n",(float)PressLevel_f); //gcs().send_text(MAV_SEVERITY_INFO, " forward lateral throttle %f %f %f \n",channel_forward->norm_input(),channel_lateral->norm_input(),channel_throttle->norm_input()); // gcs().send_text(MAV_SEVERITY_INFO, " roll pitch yaw %f %f %f \n",channel_roll->norm_input(),channel_pitch->norm_input(),channel_yaw->norm_input()); j=0; } rov_message.pressure_level = (int)PressLevel; }