control_sport.cpp 7.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195
  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. if(!control_check_barometer()) {
  12. return false;
  13. }
  14. // initialize vertical speeds and leash lengths
  15. // sets the maximum speed up and down returned by position controller
  16. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
  17. pos_control.set_max_accel_z(g.pilot_accel_z);
  18. pos_control.relax_alt_hold_controllers();
  19. //pos_control.set_alt_target(-20);//cm
  20. pos_control.set_target_to_stopping_point_z();
  21. holding_depth = true;
  22. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  23. last_roll = 0;
  24. last_pitch = 0;
  25. last_yaw = ahrs.yaw_sensor;
  26. last_input_ms = AP_HAL::millis();
  27. last_input_ms_stable = AP_HAL::millis();
  28. gcs().send_text(MAV_SEVERITY_INFO, " last_attitudeinit %d %d,%d ",(int)last_roll_s,(int)pitch_input_inc,(int)last_yaw_s);
  29. gcs().send_text(MAV_SEVERITY_INFO, " init Z target %f %f",(float)pos_control.get_pos_target().z,barometer.get_altitude());
  30. return true;
  31. }
  32. void Sub::handle_attitude_sport(){
  33. uint32_t tnow = AP_HAL::millis();
  34. // get pilot desired lean angles
  35. float target_roll, target_pitch, target_yaw;
  36. // Check if set_attitude_target_no_gps is valid
  37. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  38. Quaternion(
  39. set_attitude_target_no_gps.packet.q
  40. ).to_euler(
  41. target_roll,
  42. target_pitch,
  43. target_yaw
  44. );
  45. target_roll = 100 * degrees(target_roll);
  46. target_pitch = 100 * degrees(target_pitch);
  47. target_yaw = 100 * degrees(target_yaw);
  48. last_roll = target_roll;
  49. last_pitch = target_pitch;
  50. last_yaw = target_yaw;
  51. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  52. } else {
  53. // If we don't have a mavlink attitude target, we use the pilot's input instead
  54. //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());
  55. //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());
  56. 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());
  57. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  58. if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
  59. //last_roll = ahrs.roll_sensor;
  60. //last_pitch = ahrs.pitch_sensor;
  61. //last_yaw = ahrs.yaw_sensor;
  62. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  63. last_input_ms = tnow;
  64. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
  65. } else if (abs(target_yaw) > 300) {
  66. // if only yaw is being controlled, don't update pitch and roll
  67. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  68. //last_yaw = ahrs.yaw_sensor;
  69. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  70. last_input_ms = tnow;
  71. } else if (tnow < last_input_ms + 250) {
  72. // just brake for a few mooments so we don't bounce
  73. last_yaw = ahrs.yaw_sensor;
  74. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  75. } else {
  76. // Lock attitude
  77. //attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
  78. attitude_control.input_quaternion(attitude_desired_quat_);
  79. }
  80. static int f = 0;
  81. f++;
  82. if(f>800)
  83. {
  84. gcs().send_text(MAV_SEVERITY_INFO, " sportrpy %f %f,%f ",(float)target_roll,(float)target_pitch,(float)target_yaw);
  85. gcs().send_text(MAV_SEVERITY_INFO, " sportatd %f %f,%f ",(float)last_roll,(float)last_pitch,(float)last_yaw);
  86. f=0;
  87. }
  88. }
  89. }
  90. // althold_run - runs the althold controller
  91. // should be called at 100hz or more
  92. void Sub::sport_run()
  93. {
  94. // When unarmed, disable motors and stabilization
  95. if (!motors.armed()) {
  96. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  97. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  98. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  99. attitude_control.relax_attitude_controllers();
  100. pos_control.relax_alt_hold_controllers();
  101. //pos_control.set_alt_target(-20);//cm
  102. last_roll = 0;
  103. last_pitch = 0;
  104. last_yaw = ahrs.yaw_sensor;
  105. holding_depth = false;
  106. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  107. static int f = 0;
  108. f++;
  109. if(f>800)
  110. {
  111. gcs().send_text(MAV_SEVERITY_INFO, " disarm Z target %f %f %f",(float)pos_control.get_pos_target().z,pos_control.get_alt(),barometer.get_altitude());
  112. f=0;
  113. }
  114. return;
  115. }
  116. // Vehicle is armed, motors are free to run
  117. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  118. handle_attitude_sport();
  119. //handle_attitude();
  120. pos_control.update_z_controller();
  121. // Read the output of the z controller and rotate it so it always points up
  122. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
  123. // Output the Z controller + pilot input to all motors.
  124. //TODO: scale throttle with the ammount of thrusters in the given direction
  125. // motors.set_throttle(0.5+throttle_vehicle_frame.z + channel_throttle->norm_input()-0.5);
  126. motors.set_throttle(throttle_vehicle_frame.z + 1.0-(float)PressLevel_f*0.1);
  127. rov_message.pressure_level = int(PressLevel);
  128. motors.set_forward(-throttle_vehicle_frame.x + channel_forward->norm_input());
  129. motors.set_lateral(-throttle_vehicle_frame.y + channel_lateral->norm_input());
  130. // We rotate the RC inputs to the earth frame to check if the user is giving an input that would change the depth.
  131. //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())));
  132. 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)));
  133. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  134. // reset z targets to current values
  135. holding_depth = false;
  136. pos_control.relax_alt_hold_controllers();
  137. //pos_control.set_alt_target(barometer.get_altitude()*100);//cm
  138. } else { // hold z
  139. if (ap.at_surface) { //最大油门不能向上动
  140. pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
  141. holding_depth = true;
  142. } else if (ap.at_bottom) {//最大油门不能向下动
  143. pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
  144. //pos_control.set_alt_target(barometer.get_altitude()*100 +20);//cm
  145. holding_depth = true;
  146. } else if (!holding_depth) {
  147. pos_control.set_target_to_stopping_point_z();
  148. holding_depth = true;
  149. }
  150. }
  151. static int f = 0;
  152. f++;
  153. if(f>800)
  154. {
  155. gcs().send_text(MAV_SEVERITY_INFO, " Z target %f %f %f",(float)pos_control.get_pos_target().z,pos_control.get_alt(),barometer.get_altitude());
  156. gcs().send_text(MAV_SEVERITY_INFO, " surface %d at_bottom %d ",ap.at_surface,ap.at_bottom);
  157. f=0;
  158. }
  159. }