1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465 |
- #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();
- updowmgain =0.5;
- 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;
- updowmgain =0.5;
- return;
- }
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
- motors.set_roll(0.0);//(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(channel_lateral->norm_input());
- //motors.set_throttle(1.0-(float)PressLevel_f*0.1);//0-0.5下压
- float tt = gaindelay(1.0-(float)PressLevel_f*0.1);
- motors.set_throttle(tt);//0-0.5下压
- static int j = 0;
-
- j++;
- if(j>300)
- {
- gcs().send_text(MAV_SEVERITY_INFO, " upgain %f\n",tt);//0~1.0
- //gcs().send_text(MAV_SEVERITY_INFO, " throttle %f\n",getgainf(channel_throttle->norm_input()));//0~1.0
- // gcs().send_text(MAV_SEVERITY_INFO, " yaw %f\n",getgainf(channel_yaw->norm_input()));//-1.0~1.0
- // gcs().send_text(MAV_SEVERITY_INFO, " forward %f\n",getgainf(channel_forward->norm_input()));//-1.0~1.0
- // gcs().send_text(MAV_SEVERITY_INFO, " lateral %f\n",getgainf(channel_lateral->norm_input()));//-1.0~1.0
-
-
- // gcs().send_text(MAV_SEVERITY_INFO, " forward %d %d %d %d\n",(int16_t)channel_forward->radio_in,(int16_t)channel_forward->radio_min,(int16_t)channel_forward->radio_max,(int16_t)channel_forward->radio_trim);
- // gcs().send_text(MAV_SEVERITY_INFO, " lateral %d %d %d %d\n",(int16_t)channel_lateral->radio_in,(int16_t)channel_lateral->radio_min,(int16_t)channel_lateral->radio_max,(int16_t)channel_lateral->radio_trim);
- // gcs().send_text(MAV_SEVERITY_INFO, " throttle %d %d %d %d\n",(int16_t)channel_throttle->radio_in,(int16_t)channel_throttle->radio_min,(int16_t)channel_throttle->radio_max,(int16_t)channel_throttle->radio_trim);
- // gcs().send_text(MAV_SEVERITY_INFO, " yaw %d %d %d %d\n",(int16_t)channel_yaw->radio_in,(int16_t)channel_yaw->radio_min,(int16_t)channel_yaw->radio_max,(int16_t)channel_yaw->radio_trim);
- j=0;
- }
- rov_message.pressure_level = (int)PressLevel;
- }
|