control_sport .cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399
  1. #include "Sub.h"
  2. //#include "/AP_Math/AP_Math.h"
  3. #define PI 3.141592653589793238462643383279502884
  4. extern mavlink_rov_state_monitoring_t rov_message;
  5. Quaternion attitude_desired_quat_;
  6. //Matrix3f last_desired;
  7. /*
  8. * control_althold.pde - init and run calls for althold, flight mode
  9. */
  10. // althold_init - initialise althold controller
  11. bool Sub::sport_init()
  12. {
  13. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  14. //holding_depth = false;
  15. //检查是否有深度计存在
  16. if(!control_check_barometer()) {
  17. return false;
  18. }
  19. // initialize vertical speeds and leash lengths
  20. // sets the maximum speed up and down returned by position controller
  21. //get_pilot_speed_dn QGC PILOT 设置的值
  22. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);//(-500,500)设置最大最小速度 和刹车长度
  23. pos_control.set_max_accel_z(g.pilot_accel_z);//设置最大加速度值 和刹车长度
  24. pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
  25. pos_control.reset_I();
  26. //pos_control.set_target_to_stopping_point_z();//刹车长度 根据当前速度估计目标深度
  27. pos_control.calc_leash_length_z();//刹车长度 12.19
  28. pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度12.19
  29. holding_depth = true;
  30. //ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19 使用roll pitch =0的姿态
  31. attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);//初始化
  32. rotpitch.identity();
  33. attitude_desired_quat_.rotation_matrix(rotyaw);
  34. last_roll = 0;
  35. last_pitch = 0;
  36. updowmgain =0.5;
  37. delaygain = 401;
  38. continuous_count=0;
  39. continuous_countdec=0;
  40. last_continuous = 0;
  41. last_yaw = ahrs.yaw_sensor;
  42. last_input_ms = AP_HAL::millis();
  43. last_input_ms_stable = AP_HAL::millis();
  44. //updown_gain = 0.0;
  45. return true;
  46. }
  47. void Sub::handle_attitude_sport(){
  48. uint32_t tnow = AP_HAL::millis();
  49. // get pilot desired lean angles
  50. float target_roll, target_pitch, target_yaw;
  51. // Check if set_attitude_target_no_gps is valid
  52. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  53. Quaternion(
  54. set_attitude_target_no_gps.packet.q
  55. ).to_euler(
  56. target_roll,
  57. target_pitch,
  58. target_yaw
  59. );
  60. target_roll = 100 * degrees(target_roll);
  61. target_pitch = 100 * degrees(target_pitch);
  62. target_yaw = 100 * degrees(target_yaw);
  63. last_roll = target_roll;
  64. last_pitch = target_pitch;
  65. last_yaw = target_yaw;
  66. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  67. } else {
  68. float throttle = 2*(0.5-channel_throttle->norm_input());
  69. float yaw = channel_yaw->norm_input();
  70. if (fabsf(throttle)>=fabsf(yaw))
  71. {
  72. yaw = 0.0;
  73. }else{
  74. throttle = 0.0;
  75. yaw = channel_yaw->get_control_in()*0.35;
  76. }
  77. get_pilot_desired_lean_angles(0, (int16_t)(throttle/1.5*5700), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  78. target_yaw = get_pilot_desired_yaw_rate(yaw);//*0.6 变慢
  79. if ( abs(target_pitch) > 300) {
  80. last_input_ms = tnow;
  81. attitude_control.input_rate_bf_roll_pitch_yaw(0, target_pitch, 0);
  82. //ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  83. Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17
  84. float pitch_ang = get_pitch_to_ned(mat_body);
  85. rotpitch.from_euler(0,pitch_ang,0);//pitch 旋转矩阵
  86. } else if (abs(target_yaw) > 300) {
  87. // if only yaw is being controlled, don't update pitch and roll
  88. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  89. Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17
  90. get_heading_to_ned(rotyaw,mat_body);//yaw旋转矩阵
  91. //ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  92. last_input_ms = tnow;
  93. } else if (tnow < last_input_ms + 250) {
  94. // just brake for a few mooments so we don't bounce
  95. Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17
  96. get_heading_to_ned(rotyaw,mat_body);//yaw旋转矩阵
  97. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  98. } else {
  99. // Lock attitude
  100. float depth = barometer.get_altitude()*100; // cm
  101. if(fabsf(depth)<50){//水面附近
  102. float maxsinpitch = constrain_float(fabsf(depth)/50.0,0.0,1.0);//40深度传感器到体长+10 余量 可以允许的最大pitch角的绝对值
  103. float nowsinpitch = rotpitch.a.z;//当前的pitch角
  104. Matrix3f rotpitch_limit;
  105. if (fabsf(nowsinpitch)>maxsinpitch)//说明比允许的大 姿态应该是恢复水平一些
  106. {
  107. float pitch_ang = get_pitch_to_ned(rotpitch);//目前的pith
  108. if (fabsf(pitch_ang)<PI/2)
  109. {
  110. pitch_ang = asinf(maxsinpitch);
  111. }else{
  112. pitch_ang = (PI- asinf(maxsinpitch))*sign_in(pitch_ang);
  113. }
  114. rotpitch_limit .from_euler(0,pitch_ang,0);//pitch 旋转矩阵
  115. }else{//保持原来的姿态
  116. rotpitch_limit = rotpitch;//pitch 旋转矩阵
  117. }
  118. attitude_desired_quat_.from_rotation_matrix(rotyaw*rotpitch_limit);
  119. static uint16_t count = 0;
  120. count++;
  121. if (count>400)
  122. {
  123. count = 0;
  124. // gcs().send_text(MAV_SEVERITY_INFO, "ahr %f %f %f \n",nowsinpitch,maxsinpitch,get_pitch_to_ned(rotpitch_limit));
  125. }
  126. }else{
  127. attitude_desired_quat_.from_rotation_matrix(rotyaw*rotpitch);
  128. }
  129. attitude_control.input_quaternion(attitude_desired_quat_);
  130. //attitude_desired_quat_.from_rotation_matrix(rotyaw*rotpitch);
  131. //attitude_control.input_quaternion(attitude_desired_quat_);
  132. }
  133. }
  134. }
  135. void Sub::sport_run_alt(void){
  136. // When unarmed, disable motors and stabilization
  137. if (!motors.armed()) {
  138. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  139. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  140. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  141. attitude_control.relax_attitude_controllers();
  142. pos_control.relax_alt_hold_controllers();
  143. pos_control.reset_I();
  144. pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  145. updowmgain =0.5;
  146. last_roll = 0;
  147. last_pitch = 0;
  148. last_yaw = ahrs.yaw_sensor;
  149. holding_depth = false;
  150. rotpitch.identity();
  151. attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);//初始化
  152. attitude_desired_quat_.rotation_matrix(rotyaw);
  153. delaygain = 401;
  154. continuous_count=0;
  155. continuous_countdec=0;
  156. last_continuous = 0;
  157. return;
  158. }
  159. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  160. handle_attitude_sport();
  161. //pos_control.update_z_controller();//输出了set_throttle_out
  162. Matrix3f mat_body = ahrs.get_rotation_body_to_ned();
  163. Matrix3f mat_half;
  164. get_heading_to_ned(mat_half,mat_body);//得到half状态
  165. // mat 地到half状态
  166. Matrix3f rc_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed()*mat_half;//rc_vehicle_frame(half)到body
  167. //防止手柄交叉
  168. float forward = channel_forward->norm_input();
  169. float lateral =channel_lateral->norm_input();
  170. if (fabsf(forward)>=fabsf(lateral))
  171. {
  172. lateral = 0.0;
  173. }else{
  174. forward = 0.0;
  175. }
  176. //手柄转到机体系------------------------
  177. float joystick_z = 2*(gaindelay(1.0-(float)PressLevel_f*0.1)-0.5);//-1~1
  178. Vector3f rc_throttle_forward = Vector3f(getgainf(forward),0, 0);//手柄的值
  179. Vector3f rc_throttle_lateral = Vector3f(0, getgainf(lateral), 0);//手柄的值
  180. Vector3f rc_throttle = Vector3f(0, 0, joystick_z);//手柄的值
  181. Vector3f rc_throttle_vehicle_frame1 = rc_vehicle_frame*rc_throttle_forward;//手柄从half系到body系
  182. Vector3f rc_throttle_vehicle_frame2 = rc_vehicle_frame*rc_throttle_lateral;//手柄从half系到body系
  183. Vector3f rc_throttle_vehicle_frame3 = rc_vehicle_frame*rc_throttle;//手柄从half系到body系
  184. Vector3f rc_throttle_vehicle_frame;
  185. rc_throttle_vehicle_frame.x = rc_throttle_vehicle_frame1.x + rc_throttle_vehicle_frame2.x - rc_throttle_vehicle_frame3.x;
  186. rc_throttle_vehicle_frame.y = rc_throttle_vehicle_frame1.y + rc_throttle_vehicle_frame2.y - rc_throttle_vehicle_frame3.y;
  187. rc_throttle_vehicle_frame.z = -rc_throttle_vehicle_frame1.z - rc_throttle_vehicle_frame2.z + rc_throttle_vehicle_frame3.z;
  188. //----------------------------------------------------
  189. // Read the output of the z controller and rotate it so it always points up
  190. //深度保持控制
  191. float z_throttle = pos_control.update_z_controller_f();//输出了垂直变化量
  192. //将深度保持控制的对地系转到机体系
  193. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);//变到机体坐标系
  194. //手柄控制和深度保持的Z轴输出的叠加
  195. motors.set_forward(-throttle_vehicle_frame.x +rc_throttle_vehicle_frame.x);
  196. motors.set_lateral(-throttle_vehicle_frame.y +rc_throttle_vehicle_frame.y);
  197. motors.set_throttle(throttle_vehicle_frame.z +rc_throttle_vehicle_frame.z/2+0.5);
  198. rov_message.pressure_level = int(PressLevel);
  199. Vector3f earth_frame_rc_inputs = Vector3f(0.0, 0.0, joystick_z);//仅仅与竖直有关 手柄是在half系 Z轴
  200. bottom_detectorgain();
  201. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  202. // reset z targets to current values
  203. holding_depth = false;
  204. pos_control.relax_alt_hold_controllers();
  205. } else { // hold z
  206. if (ap.at_surface) { //最大油门不能向上动
  207. pos_control.set_alt_target(surface_depth_use()*100 - 10.0f); // set target to 5cm below surface level
  208. holding_depth = true;
  209. } else if (ap.at_bottom||bottom_set) {//最大油门不能向下动
  210. //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
  211. pos_control.set_alt_target(barometer.get_altitude()*100 +10);//cm
  212. holding_depth = true;
  213. } else if (!holding_depth) {
  214. pos_control.calc_leash_length_z();//刹车长度 12.19
  215. // pos_control.set_target_to_stopping_point_z();//有对位置的付值
  216. pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
  217. holding_depth = true;
  218. }
  219. }
  220. static bool lastdepth = holding_depth;
  221. if(lastdepth !=holding_depth){
  222. lastdepth = holding_depth;
  223. //gcs().send_text(MAV_SEVERITY_INFO, "get_alt %d %f %f\n",(int)holding_depth,pos_control.get_alt_target(),barometer.get_altitude()*100);
  224. }
  225. static uint16_t count = 0;
  226. count++;
  227. if (count>400)
  228. {
  229. count = 0;
  230. // gcs().send_text(MAV_SEVERITY_INFO, "surf %d %d %d %f\n",(int)ap.at_surface,(int)ap.at_bottom,(int)motors.limit.throttle_upper,(float)motors.get_throttle());
  231. // gcs().send_text(MAV_SEVERITY_INFO, "alt %f %f %f %f\n",pos_control.get_alt_target(),barometer.get_altitude()*100,pos_control.alt_rate.get(),joystick_z);
  232. }
  233. }
  234. void Sub::altcontrol(){//相对机体系的手柄控制
  235. //深度控制
  236. float z_throttle = pos_control.update_z_controller_f();//输出了set_throttle_out
  237. //变到机体坐标系
  238. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);
  239. // Output the Z controller + pilot input to all motors.
  240. float z_throttle_joystic = gaindelay(1.0-(float)PressLevel_f*0.1);//0~1
  241. motors.set_throttle(throttle_vehicle_frame.z + z_throttle_joystic);//Z轴油门
  242. rov_message.pressure_level = int(PressLevel);
  243. //防止交叉
  244. float forward = channel_forward->norm_input();
  245. float lateral =channel_lateral->norm_input();
  246. if (fabsf(forward)>=fabsf(lateral))
  247. {
  248. lateral = 0.0;
  249. }else{
  250. forward = 0.0;
  251. }
  252. //变换到集体轴
  253. if (control_mode == SPORT)
  254. {
  255. motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainf(forward),-0.8,0.8));//*0.6 变慢
  256. motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainf(lateral),-0.8,0.8));//*0.6 变慢
  257. }else{
  258. motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainfstatble(forward),-1.0,1.0));//
  259. motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainfstatble(lateral),-1.0,1.0));//
  260. }
  261. Vector3f earth_frame_rc_inputs1 = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), 0.0, (z_throttle_joystic-0.5)*2);//去掉侧移影响
  262. bottom_detectorgain();
  263. if (fabsf(earth_frame_rc_inputs1.z) > 0.05f) { // Throttle input above 5%
  264. // reset z targets to current values
  265. holding_depth = false;
  266. pos_control.relax_alt_hold_controllers();
  267. } else { // hold z
  268. if (ap.at_surface) { //最大油门不能向上动
  269. pos_control.set_alt_target(surface_depth_use()*100 - 10.0f); // set target to 5cm below surface level
  270. holding_depth = true;
  271. } else if (ap.at_bottom||bottom_set) {//最大油门不能向下动
  272. pos_control.set_alt_target(barometer.get_altitude()*100+10);//cm
  273. holding_depth = true;
  274. } else if (!holding_depth) {
  275. pos_control.calc_leash_length_z();//刹车长度 12.19
  276. pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
  277. holding_depth = true;
  278. }
  279. }
  280. static bool lastdepth = holding_depth;
  281. if(lastdepth !=holding_depth){
  282. lastdepth = holding_depth;
  283. gcs().send_text(MAV_SEVERITY_INFO, " get_alt_target %d %f \n",(int)holding_depth,motors.get_throttle());
  284. }
  285. static uint16_t count = 0;
  286. count++;
  287. if (count>300)
  288. {
  289. count = 0;
  290. gcs().send_text(MAV_SEVERITY_INFO, " surface %d %d %d\n",(int)ap.at_surface,(int)ap.at_bottom,(int)motors.limit.throttle_upper);
  291. gcs().send_text(MAV_SEVERITY_INFO, " altitude %f %f %f\n",pos_control.get_alt_target(),barometer.get_altitude()*100,motors.get_throttle());
  292. }
  293. }