1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465 |
- #include "Sub.h"
- bool Sub::manual_init()
- {
-
- pos_control.set_alt_target(0);
-
-
- set_neutral_controls();
- updowmgain =0.5;
- return true;
- }
- extern mavlink_rov_state_monitoring_t rov_message;
- void Sub::manual_run()
- {
-
- 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);
- motors.set_pitch((0.5-channel_throttle->norm_input())*2);
- 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());
-
- float tt = gaindelay(1.0-(float)PressLevel_f*0.1);
- motors.set_throttle(tt);
- static int j = 0;
-
- j++;
- if(j>300)
- {
- gcs().send_text(MAV_SEVERITY_INFO, " upgain %f\n",tt);
-
-
-
-
-
-
-
-
-
-
- j=0;
- }
- rov_message.pressure_level = (int)PressLevel;
- }
|