control_sport.dak 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431
  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. /*
  7. * control_althold.pde - init and run calls for althold, flight mode
  8. */
  9. // althold_init - initialise althold controller
  10. bool Sub::sport_init()
  11. {
  12. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  13. //holding_depth = false;
  14. //检查是否有深度计存在
  15. if(!control_check_barometer()) {
  16. return false;
  17. }
  18. // initialize vertical speeds and leash lengths
  19. // sets the maximum speed up and down returned by position controller
  20. //get_pilot_speed_dn QGC PILOT 设置的值
  21. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);//(-500,500)设置最大最小速度 和刹车长度
  22. pos_control.set_max_accel_z(g.pilot_accel_z);//设置最大加速度值 和刹车长度
  23. pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
  24. //
  25. //pos_control.set_target_to_stopping_point_z();//刹车长度 根据当前速度估计目标深度
  26. pos_control.calc_leash_length_z();//刹车长度 12.19
  27. pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度12.19
  28. holding_depth = true;
  29. //ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19 使用roll pitch =0的姿态
  30. attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);
  31. last_roll = 0;
  32. last_pitch = 0;
  33. updowmgain =0.5;
  34. last_yaw = ahrs.yaw_sensor;
  35. last_input_ms = AP_HAL::millis();
  36. last_input_ms_stable = AP_HAL::millis();
  37. return true;
  38. }
  39. void Sub::handle_attitude_sport(){
  40. uint32_t tnow = AP_HAL::millis();
  41. // get pilot desired lean angles
  42. float target_roll, target_pitch, target_yaw;
  43. // Check if set_attitude_target_no_gps is valid
  44. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  45. Quaternion(
  46. set_attitude_target_no_gps.packet.q
  47. ).to_euler(
  48. target_roll,
  49. target_pitch,
  50. target_yaw
  51. );
  52. target_roll = 100 * degrees(target_roll);
  53. target_pitch = 100 * degrees(target_pitch);
  54. target_yaw = 100 * degrees(target_yaw);
  55. last_roll = target_roll;
  56. last_pitch = target_pitch;
  57. last_yaw = target_yaw;
  58. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  59. } else {
  60. float throttle = 2*(0.5-channel_throttle->norm_input());
  61. float yaw = channel_yaw->norm_input();
  62. if (fabsf(throttle)>=fabsf(yaw))
  63. {
  64. yaw = 0.0;
  65. }else{
  66. throttle = 0.0;
  67. yaw = channel_yaw->get_control_in()*0.3;
  68. }
  69. get_pilot_desired_lean_angles(0, (int16_t)(throttle/2.0*5700), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  70. target_yaw = get_pilot_desired_yaw_rate(yaw);//*0.6 变慢
  71. if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
  72. //last_roll = ahrs.roll_sensor;
  73. //last_pitch = ahrs.pitch_sensor;
  74. //last_yaw = ahrs.yaw_sensor;
  75. last_input_ms = tnow;
  76. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
  77. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  78. } else if (abs(target_yaw) > 300) {
  79. // if only yaw is being controlled, don't update pitch and roll
  80. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  81. //last_yaw = ahrs.yaw_sensor;
  82. ahrs.get_quat_body_to_ned(attitude_desired_quat_);
  83. last_input_ms = tnow;
  84. } else if (tnow < last_input_ms + 250) {
  85. // just brake for a few mooments so we don't bounce
  86. last_yaw = ahrs.yaw_sensor;
  87. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  88. } else {
  89. // Lock attitude
  90. //attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
  91. attitude_control.input_quaternion(attitude_desired_quat_);
  92. }
  93. }
  94. }
  95. void Sub::sport_run_alt(void){
  96. // When unarmed, disable motors and stabilization
  97. if (!motors.armed()) {
  98. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  99. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  100. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  101. attitude_control.relax_attitude_controllers();
  102. pos_control.relax_alt_hold_controllers();
  103. pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  104. updowmgain =0.5;
  105. last_roll = 0;
  106. last_pitch = 0;
  107. last_yaw = ahrs.yaw_sensor;
  108. holding_depth = false;
  109. // ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
  110. attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);
  111. return;
  112. }
  113. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  114. handle_attitude_sport();
  115. //pos_control.update_z_controller();//输出了set_throttle_out
  116. Matrix3f mat_body = ahrs.get_rotation_body_to_ned();
  117. //Vector3f Zb = mat_body*Vector3f(0,0,1);
  118. //Vector3f Ze = Vector3f(0,0,1);
  119. //float thetaz = Zb*Ze;//计算有没有翻过来
  120. Matrix3f mat_half;
  121. float beta = 0.0;
  122. float dot=0.0;
  123. if(mat_body.c.x<0.98 && mat_body.c.x>-0.98){//大约78.5度认为Z轴指向方向,小于78.5进入X轴指向方向
  124. Vector3f Xbx = mat_body*Vector3f(1,0,0);
  125. Xbx.z = 0.0;
  126. Vector3f Xex = Vector3f(1,0,0);
  127. dot = Xbx * Xex/Xbx.length();
  128. beta = acosf(dot );
  129. if (Xbx.y<0)
  130. {
  131. beta = -beta;
  132. }
  133. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  134. Vector3f Xez = Vector3f(0,0,1);
  135. float dotz = Xbz * Xez/Xbz.length();
  136. if (dotz<0)
  137. {
  138. beta = beta-PI;
  139. if (beta<-PI)
  140. {
  141. beta = beta+2*PI;
  142. }
  143. }
  144. mat_half.a.x= cosf(beta);
  145. mat_half.a.y=-sinf(beta);
  146. mat_half.a.z=0.0;
  147. mat_half.b.x= sinf(beta);
  148. mat_half.b.y= cosf(beta);
  149. mat_half.b.z=0.0;
  150. mat_half.c.x= 0.0;
  151. mat_half.c.y= 0.0;
  152. mat_half.c.z=1.0;
  153. }
  154. else{
  155. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  156. Xbz.z = 0.0;
  157. Vector3f Xex = Vector3f(1,0,0);
  158. dot = Xbz * Xex/Xbz.length();
  159. beta = acosf(dot );
  160. if (Xbz.y<0)
  161. {
  162. beta = -beta;
  163. }
  164. if (mat_body.c.x>0)//头朝下
  165. {
  166. beta = beta-PI;
  167. if (beta<-PI)
  168. {
  169. beta = beta+2*PI;
  170. }
  171. }
  172. mat_half.a.x= cosf(beta);
  173. mat_half.a.y=-sinf(beta);
  174. mat_half.a.z=0.0;
  175. mat_half.b.x= sinf(beta);
  176. mat_half.b.y= cosf(beta);
  177. mat_half.b.z=0.0;
  178. mat_half.c.x= 0.0;
  179. mat_half.c.y= 0.0;
  180. mat_half.c.z=1.0;
  181. }
  182. // mat 地到half状态
  183. Matrix3f rc_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed()*mat_half;//rc_vehicle_frame(half)到body
  184. float forward = channel_forward->norm_input();
  185. float lateral =channel_lateral->norm_input();
  186. if (fabsf(forward)>=fabsf(lateral))
  187. {
  188. lateral = 0.0;
  189. }else{
  190. forward = 0.0;
  191. }
  192. Vector3f rc_throttle_forward = Vector3f(getgainf(forward),0, 0);//手柄的值
  193. Vector3f rc_throttle_lateral = Vector3f(0, getgainf(lateral), 0);//手柄的值
  194. Vector3f rc_throttle = Vector3f(0, 0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//手柄的值
  195. Vector3f rc_throttle_vehicle_frame1 = rc_vehicle_frame*rc_throttle_forward;//手柄从half系到body系
  196. Vector3f rc_throttle_vehicle_frame2 = rc_vehicle_frame*rc_throttle_lateral;//手柄从half系到body系
  197. Vector3f rc_throttle_vehicle_frame3 = rc_vehicle_frame*rc_throttle;//手柄从half系到body系
  198. Vector3f rc_throttle_vehicle_frame;
  199. rc_throttle_vehicle_frame.x = rc_throttle_vehicle_frame1.x + rc_throttle_vehicle_frame2.x - rc_throttle_vehicle_frame3.x;
  200. rc_throttle_vehicle_frame.y = rc_throttle_vehicle_frame1.y + rc_throttle_vehicle_frame2.y - rc_throttle_vehicle_frame3.y;
  201. rc_throttle_vehicle_frame.z = -rc_throttle_vehicle_frame1.z - rc_throttle_vehicle_frame2.z + rc_throttle_vehicle_frame3.z;
  202. // Read the output of the z controller and rotate it so it always points up
  203. //将Z轴输出变到机体坐标系
  204. //Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
  205. float z_throttle = pos_control.update_z_controller_f();//输出了set_throttle_out
  206. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);
  207. //手柄控制和Z轴输出的叠加
  208. motors.set_forward(-throttle_vehicle_frame.x +rc_throttle_vehicle_frame.x);
  209. motors.set_lateral(-throttle_vehicle_frame.y +rc_throttle_vehicle_frame.y);//*0.6 变慢
  210. motors.set_throttle(throttle_vehicle_frame.z +rc_throttle_vehicle_frame.z/2+0.5);
  211. rov_message.pressure_level = int(PressLevel);
  212. Vector3f earth_frame_rc_inputs = Vector3f(0.0, 0.0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//去掉侧移影响
  213. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  214. // reset z targets to current values
  215. holding_depth = false;
  216. pos_control.relax_alt_hold_controllers();
  217. } else { // hold z
  218. if (ap.at_surface) { //最大油门不能向上动
  219. pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
  220. holding_depth = true;
  221. } else if (ap.at_bottom) {//最大油门不能向下动
  222. //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
  223. pos_control.set_alt_target(barometer.get_altitude()*100 +10);//cm
  224. holding_depth = true;
  225. } else if (!holding_depth) {
  226. pos_control.calc_leash_length_z();//刹车长度 12.19
  227. // pos_control.set_target_to_stopping_point_z();//有对位置的付值
  228. pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
  229. holding_depth = true;
  230. }
  231. }
  232. static bool lastdepth = holding_depth;
  233. if(lastdepth !=holding_depth){
  234. lastdepth = holding_depth;
  235. gcs().send_text(MAV_SEVERITY_INFO, "get_alt_target %d %f %f\n",(int)holding_depth,pos_control.get_alt_target(),barometer.get_altitude()*100);
  236. }
  237. static uint16_t count = 0;
  238. count++;
  239. if (count>300)
  240. {
  241. count = 0;
  242. 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(),motors.get_throttle());
  243. gcs().send_text(MAV_SEVERITY_INFO, "surf %d %d %f \n",(int)ap.at_surface,(int)ap.at_bottom,motors.get_throttle_thrust_max());
  244. }
  245. }
  246. void Sub::altcontrol(){
  247. float z_throttle = pos_control.update_z_controller_f();//输出了set_throttle_out
  248. // Read the output of the z controller and rotate it so it always points up
  249. //变到机体坐标系
  250. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);
  251. // Output the Z controller + pilot input to all motors.
  252. motors.set_throttle(throttle_vehicle_frame.z + gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain));
  253. static uint16_t j=0;
  254. j++;
  255. if(j>300)
  256. {
  257. gcs().send_text(MAV_SEVERITY_INFO, " sportthrottle %f %f %f \n",z_throttle,throttle_vehicle_frame.z,motors.get_throttle());
  258. j=0;
  259. }
  260. rov_message.pressure_level = int(PressLevel);
  261. float forward = channel_forward->norm_input();
  262. float lateral =channel_lateral->norm_input();
  263. if (fabsf(forward)>=fabsf(lateral))
  264. {
  265. lateral = 0.0;
  266. }else{
  267. forward = 0.0;
  268. }
  269. motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainf(forward),-0.8,0.8));//*0.6 变慢
  270. motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainf(lateral),-0.8,0.8));//*0.6 变慢
  271. Vector3f earth_frame_rc_inputs1 = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), 0.0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//去掉侧移影响
  272. if (fabsf(earth_frame_rc_inputs1.z) > 0.05f) { // Throttle input above 5%
  273. // reset z targets to current values
  274. holding_depth = false;
  275. pos_control.relax_alt_hold_controllers();
  276. //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  277. } else { // hold z
  278. if (ap.at_surface) { //最大油门不能向上动
  279. pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
  280. holding_depth = true;
  281. } else if (ap.at_bottom) {//最大油门不能向下动
  282. //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
  283. pos_control.set_alt_target(barometer.get_altitude()*100+10);//cm
  284. holding_depth = true;
  285. } else if (!holding_depth) {
  286. pos_control.calc_leash_length_z();//刹车长度 12.19
  287. pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
  288. holding_depth = true;
  289. }
  290. }
  291. static bool lastdepth = holding_depth;
  292. if(lastdepth !=holding_depth){
  293. lastdepth = holding_depth;
  294. gcs().send_text(MAV_SEVERITY_INFO, " get_alt_target %d %f \n",(int)holding_depth,motors.get_throttle());
  295. }
  296. static uint16_t count = 0;
  297. count++;
  298. if (count>300)
  299. {
  300. count = 0;
  301. gcs().send_text(MAV_SEVERITY_INFO, " surface %d %d %d\n",(int)ap.at_surface,(int)ap.at_bottom,(int)motors.limit.throttle_lower);
  302. gcs().send_text(MAV_SEVERITY_INFO, " altitude %f %f \n",pos_control.get_alt_target(),barometer.get_altitude()*100);
  303. }
  304. }
  305. // althold_run - runs the althold controller
  306. // should be called at 100hz or more
  307. void Sub::sport_run()
  308. {
  309. // When unarmed, disable motors and stabilization
  310. if (!motors.armed()) {
  311. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  312. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  313. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  314. attitude_control.relax_attitude_controllers();
  315. pos_control.relax_alt_hold_controllers();
  316. //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
  317. updowmgain =0.5;
  318. last_roll = 0;
  319. last_pitch = 0;
  320. last_yaw = ahrs.yaw_sensor;
  321. holding_depth = false;
  322. ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
  323. return;
  324. }
  325. // Vehicle is armed, motors are free to run
  326. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  327. handle_attitude_sport();
  328. altcontrol();
  329. }