control_sport.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229
  1. #include "Sub.h"
  2. //#include "/AP_Math/AP_Math.h"
  3. extern mavlink_rov_state_monitoring_t rov_message;
  4. Quaternion attitude_desired_quat_;
  5. /*
  6. * control_althold.pde - init and run calls for althold, flight mode
  7. */
  8. // althold_init - initialise althold controller
  9. bool Sub::sport_init()
  10. {
  11. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  12. //holding_depth = false;
  13. //检查是否有深度计存在
  14. if(!control_check_barometer()) {
  15. return false;
  16. }
  17. // initialize vertical speeds and leash lengths
  18. // sets the maximum speed up and down returned by position controller
  19. //get_pilot_speed_dn QGC PILOT 设置的值
  20. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);//(-500,500)设置最大最小速度 和刹车长度
  21. pos_control.set_max_accel_z(g.pilot_accel_z);//设置最大加速度值 和刹车长度
  22. pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
  23. //
  24. //pos_control.set_target_to_stopping_point_z();//刹车长度 根据当前速度估计目标深度
  25. pos_control.calc_leash_length_z();//刹车长度 12.19
  26. pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度12.19
  27. holding_depth = true;
  28. ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
  29. last_roll = 0;
  30. last_pitch = 0;
  31. updowmgain =0.5;
  32. last_yaw = ahrs.yaw_sensor;
  33. last_input_ms = AP_HAL::millis();
  34. last_input_ms_stable = AP_HAL::millis();
  35. return true;
  36. }
  37. void Sub::handle_attitude_sport(){
  38. uint32_t tnow = AP_HAL::millis();
  39. // get pilot desired lean angles
  40. float target_roll, target_pitch, target_yaw;
  41. // Check if set_attitude_target_no_gps is valid
  42. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  43. Quaternion(
  44. set_attitude_target_no_gps.packet.q
  45. ).to_euler(
  46. target_roll,
  47. target_pitch,
  48. target_yaw
  49. );
  50. target_roll = 100 * degrees(target_roll);
  51. target_pitch = 100 * degrees(target_pitch);
  52. target_yaw = 100 * degrees(target_yaw);
  53. last_roll = target_roll;
  54. last_pitch = target_pitch;
  55. last_yaw = target_yaw;
  56. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  57. } else {
  58. // If we don't have a mavlink attitude target, we use the pilot's input instead
  59. //get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  60. //get_pilot_desired_lean_angles((int16_t)(channel_lateral->norm_input()*5700), (int16_t)((0.5-channel_throttle->norm_input())*5700*2), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  61. //get_pilot_desired_lean_angles(0, (int16_t)((0.5-channel_throttle->norm_input())*5700*2), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  62. get_pilot_desired_lean_angles(0, (int16_t)((0.5-channel_throttle->norm_input())*5700), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  63. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()*0.3);//*0.6 变慢
  64. if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
  65. //last_roll = ahrs.roll_sensor;
  66. //last_pitch = ahrs.pitch_sensor;
  67. //last_yaw = ahrs.yaw_sensor;
  68. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  69. last_input_ms = tnow;
  70. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
  71. } else if (abs(target_yaw) > 300) {
  72. // if only yaw is being controlled, don't update pitch and roll
  73. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  74. //last_yaw = ahrs.yaw_sensor;
  75. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  76. last_input_ms = tnow;
  77. } else if (tnow < last_input_ms + 250) {
  78. // just brake for a few mooments so we don't bounce
  79. last_yaw = ahrs.yaw_sensor;
  80. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  81. } else {
  82. // Lock attitude
  83. //attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
  84. attitude_control.input_quaternion(attitude_desired_quat_);
  85. }
  86. }
  87. }
  88. // althold_run - runs the althold controller
  89. // should be called at 100hz or more
  90. void Sub::sport_run()
  91. {
  92. // When unarmed, disable motors and stabilization
  93. if (!motors.armed()) {
  94. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  95. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  96. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  97. attitude_control.relax_attitude_controllers();
  98. pos_control.relax_alt_hold_controllers();
  99. //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  100. updowmgain =0.5;
  101. last_roll = 0;
  102. last_pitch = 0;
  103. last_yaw = ahrs.yaw_sensor;
  104. holding_depth = false;
  105. ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
  106. return;
  107. }
  108. // Vehicle is armed, motors are free to run
  109. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  110. handle_attitude_sport();
  111. //handle_attitude();
  112. pos_control.update_z_controller();
  113. // Read the output of the z controller and rotate it so it always points up
  114. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
  115. // Output the Z controller + pilot input to all motors.
  116. //TODO: scale throttle with the ammount of thrusters in the given direction
  117. // motors.set_throttle(0.5+throttle_vehicle_frame.z + channel_throttle->norm_input()-0.5);
  118. // motors.set_throttle(throttle_vehicle_frame.z + 1.0-(float)PressLevel_f*0.1);
  119. motors.set_throttle(throttle_vehicle_frame.z + gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain));
  120. rov_message.pressure_level = int(PressLevel);
  121. motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainf(channel_forward->norm_input()),-0.8,0.8));//*0.6 变慢
  122. motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainf(channel_lateral->norm_input()),-0.8,0.8));//*0.6 变慢
  123. // We rotate the RC inputs to the earth frame to check if the user is giving an input that would change the depth.
  124. //Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0f*(-0.5f+channel_throttle->norm_input())));
  125. //Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0*(0.5-PressLevel_f*0.1)));
  126. Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), 0.0, (2.0*(0.5-PressLevel_f*0.1)));//去掉侧移影响
  127. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  128. // reset z targets to current values
  129. holding_depth = false;
  130. pos_control.relax_alt_hold_controllers();
  131. //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  132. } else { // hold z
  133. if (ap.at_surface) { //最大油门不能向上动
  134. pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
  135. holding_depth = true;
  136. } else if (ap.at_bottom) {//最大油门不能向下动
  137. //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
  138. pos_control.set_alt_target(barometer.get_altitude()*100 +20);//cm
  139. holding_depth = true;
  140. } else if (!holding_depth) {
  141. //pos_control.set_target_to_stopping_point_z();//有对位置的付值
  142. pos_control.calc_leash_length_z();//刹车长度 12.19
  143. pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
  144. holding_depth = true;
  145. }
  146. }
  147. }
  148. /*
  149. float rmpforward(float _gain){
  150. static uint16_t rmpcounter = 0;
  151. float get_forward_gain = motors.get_forward();
  152. float temp=0;
  153. rmpcounter++;
  154. if (rmpcounter>20)
  155. {
  156. rmpcounter =0;
  157. if(get_forward_gain - _gain>0.01){
  158. temp = get_forward_gain-0.01;
  159. }else if(get_forward_gain- _gain<-0.01){
  160. temp = get_forward_gain+0.01;
  161. }
  162. else{
  163. temp = _gain;
  164. }
  165. }
  166. if (_gain>0.3)
  167. {
  168. temp =constrain_float(temp,0.4,1.0);
  169. }else if(temp<-0.3){
  170. temp = constrain_float(temp,-1.0,-0.4);
  171. }else{
  172. temp=0.0;
  173. }
  174. }*/