joystick.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893
  1. #include "Sub.h"
  2. // Functions that will handle joystick/gamepad input
  3. // ----------------------------------------------------------------------------
  4. // Anonymous namespace to hold variables used only in this file
  5. namespace {
  6. float cam_tilt = 1500.0;
  7. float cam_pan = 1500.0;
  8. int16_t lights1 = 0;
  9. int16_t lights2 = 0;
  10. int16_t rollTrim = 0;
  11. int16_t pitchTrim = 0;
  12. int16_t zTrim = 0;
  13. int16_t xTrim = 0;
  14. int16_t yTrim = 0;
  15. int16_t video_switch = 1100;
  16. int16_t x_last, y_last, z_last;
  17. uint16_t buttons_prev;
  18. // Servo control output channels
  19. // TODO: Allow selecting output channels
  20. const uint8_t SERVO_CHAN_1 = 9; // Pixhawk Aux1
  21. const uint8_t SERVO_CHAN_2 = 10; // Pixhawk Aux2
  22. const uint8_t SERVO_CHAN_3 = 11; // Pixhawk Aux3
  23. uint8_t roll_pitch_flag = false; // Flag to adjust roll/pitch instead of forward/lateral
  24. bool controls_reset_since_input_hold = true;
  25. }
  26. void Sub::init_joystick()
  27. {
  28. default_js_buttons();
  29. lights1 = 0;
  30. lights2 = 0;
  31. set_mode(MANUAL, MODE_REASON_TX_COMMAND); // Initialize flight mode
  32. if (g.numGainSettings < 1) {
  33. g.numGainSettings.set_and_save(1);
  34. }
  35. if (g.numGainSettings == 1 || (g.gain_default < g.maxGain + 0.01 && g.gain_default > g.minGain - 0.01)) {
  36. gain = constrain_float(g.gain_default, g.minGain, g.maxGain); // Use default gain parameter
  37. } else {
  38. // Use setting closest to average of minGain and maxGain
  39. gain = g.minGain + (g.numGainSettings/2 - 1) * (g.maxGain - g.minGain) / (g.numGainSettings - 1);
  40. }
  41. gain = constrain_float(gain, 0.1, 1.0);
  42. }
  43. void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
  44. {
  45. float rpyScale = 0.5*gain; // Scale -1000-1000 to -400-400 with gain
  46. float throttleScale = 1.0*gain*g.throttle_gain; // Scale 0-1000 to 0-800 times gain
  47. int16_t rpyCenter = 1500;
  48. int16_t throttleBase = 1500-500*throttleScale;
  49. bool shift = false;
  50. // Neutralize camera tilt and pan speed setpoint
  51. cam_tilt = 1500;
  52. cam_pan = 1500;
  53. // Detect if any shift button is pressed
  54. for (uint8_t i = 0 ; i < 16 ; i++) {
  55. if ((buttons & (1 << i)) && get_button(i)->function() == JSButton::button_function_t::k_shift) {
  56. shift = true;
  57. }
  58. }
  59. // Act if button is pressed
  60. // Only act upon pressing button and ignore holding. This provides compatibility with Taranis as joystick.
  61. for (uint8_t i = 0 ; i < 16 ; i++) {
  62. if ((buttons & (1 << i))) {
  63. handle_jsbutton_press(i,shift,(buttons_prev & (1 << i)));
  64. // buttonDebounce = tnow_ms;
  65. } else if (buttons_prev & (1 << i)) {
  66. handle_jsbutton_release(i, shift);
  67. }
  68. }
  69. buttons_prev = buttons;
  70. // attitude mode:
  71. if (roll_pitch_flag == 1) {
  72. // adjust roll/pitch trim with joystick input instead of forward/lateral
  73. pitchTrim = -x * rpyScale;
  74. rollTrim = y * rpyScale;
  75. }
  76. uint32_t tnow = AP_HAL::millis();
  77. int16_t zTot;
  78. int16_t yTot;
  79. int16_t xTot;
  80. if (!controls_reset_since_input_hold) {
  81. zTot = zTrim + 500; // 500 is neutral for throttle
  82. yTot = yTrim;
  83. xTot = xTrim;
  84. // if all 3 axes return to neutral, than we're ready to accept input again
  85. controls_reset_since_input_hold = (abs(z - 500) < 50) && (abs(y) < 50) && (abs(x) < 50);
  86. } else {
  87. zTot = z + zTrim;
  88. yTot = y + yTrim;
  89. xTot = x + xTrim;
  90. }
  91. RC_Channels::set_override(0, constrain_int16(pitchTrim + rpyCenter,1000,2000), tnow); // pitch
  92. RC_Channels::set_override(1, constrain_int16(rollTrim + rpyCenter,1000,2000), tnow); // roll
  93. RC_Channels::set_override(2, constrain_int16((zTot)*throttleScale+throttleBase,1000,2000), tnow); // throttle
  94. RC_Channels::set_override(3, constrain_int16(r*rpyScale+rpyCenter,1000,2000), tnow); // yaw
  95. // maneuver mode:
  96. if (roll_pitch_flag == 0) {
  97. // adjust forward and lateral with joystick input instead of roll and pitch
  98. RC_Channels::set_override(4, constrain_int16((xTot)*rpyScale+rpyCenter,1000,2000), tnow); // forward for ROV
  99. RC_Channels::set_override(5, constrain_int16((yTot)*rpyScale+rpyCenter,1000,2000), tnow); // lateral for ROV
  100. } else {
  101. // neutralize forward and lateral input while we are adjusting roll and pitch
  102. RC_Channels::set_override(4, constrain_int16(xTrim*rpyScale+rpyCenter,1000,2000), tnow); // forward for ROV
  103. RC_Channels::set_override(5, constrain_int16(yTrim*rpyScale+rpyCenter,1000,2000), tnow); // lateral for ROV
  104. }
  105. RC_Channels::set_override(6, cam_pan, tnow); // camera pan
  106. RC_Channels::set_override(7, cam_tilt, tnow); // camera tilt
  107. // RC_Channels::set_override(8, lights1, tnow); // lights 1
  108. // RC_Channels::set_override(9, lights2, tnow); // lights 2
  109. RC_Channels::set_override(10, video_switch, tnow); // video switch
  110. lights1 =constrain_int16(lights1, 0, 20000);
  111. lights2 =constrain_int16(lights2, 0, 20000);
  112. // Store old x, y, z values for use in input hold logic
  113. x_last = x;
  114. y_last = y;
  115. z_last = z;
  116. }
  117. void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
  118. {
  119. // Used for trimming level in vehicle frame
  120. Quaternion attitudeTarget;
  121. attitudeTarget.from_euler(
  122. radians(last_roll * 0.01f),
  123. radians(last_pitch * 0.01f),
  124. radians(last_yaw * 0.01f)
  125. );
  126. Vector3f localPitch = Vector3f(0, 1, 0);
  127. Vector3f localRoll = Vector3f(1, 0, 0);
  128. // Act based on the function assigned to this button
  129. switch (get_button(button)->function(shift)) {
  130. case JSButton::button_function_t::k_arm_toggle:
  131. if (motors.armed()) {
  132. arming.disarm();
  133. } else {
  134. arming.arm(AP_Arming::Method::MAVLINK);
  135. }
  136. break;
  137. case JSButton::button_function_t::k_arm:
  138. arming.arm(AP_Arming::Method::MAVLINK);
  139. break;
  140. case JSButton::button_function_t::k_disarm:
  141. if (!held) {
  142. PressLevel = no;
  143. PressLevel_f =5.0;
  144. prepare_state = Horizontal;
  145. motor1_speed_target =0;
  146. motor2_speed_target =0;
  147. track_motor_arm=1;
  148. }
  149. arming.disarm();
  150. break;
  151. case JSButton::button_function_t::k_mode_manual:
  152. set_mode(MANUAL, MODE_REASON_TX_COMMAND);
  153. break;
  154. case JSButton::button_function_t::k_mode_stabilize:
  155. set_mode(STABILIZE, MODE_REASON_TX_COMMAND);
  156. break;
  157. case JSButton::button_function_t::k_mode_depth_hold:
  158. set_mode(ALT_HOLD, MODE_REASON_TX_COMMAND);
  159. break;
  160. case JSButton::button_function_t::k_mode_auto:
  161. set_mode(AUTO, MODE_REASON_TX_COMMAND);
  162. break;
  163. case JSButton::button_function_t::k_mode_guided:
  164. set_mode(GUIDED, MODE_REASON_TX_COMMAND);
  165. break;
  166. case JSButton::button_function_t::k_mode_circle:
  167. set_mode(CIRCLE, MODE_REASON_TX_COMMAND);
  168. break;
  169. case JSButton::button_function_t::k_mode_acro:
  170. set_mode(ACRO, MODE_REASON_TX_COMMAND);
  171. break;
  172. case JSButton::button_function_t::k_mode_poshold:
  173. set_mode(POSHOLD, MODE_REASON_TX_COMMAND);
  174. break;
  175. case JSButton::button_function_t::k_mode_clean:
  176. set_mode(CLEAN, MODE_REASON_TX_COMMAND);
  177. break;
  178. case JSButton::button_function_t::k_mode_sport:
  179. set_mode(SPORT, MODE_REASON_TX_COMMAND);
  180. break;
  181. case JSButton::button_function_t::k_mount_center:
  182. #if MOUNT == ENABLED
  183. camera_mount.set_angle_targets(0, 0, 0);
  184. // for some reason the call to set_angle_targets changes the mode to mavlink targeting!
  185. camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
  186. #endif
  187. break;
  188. case JSButton::button_function_t::k_mount_tilt_up:
  189. cam_tilt = 1900;
  190. break;
  191. case JSButton::button_function_t::k_mount_tilt_down:
  192. cam_tilt = 1100;
  193. break;
  194. case JSButton::button_function_t::k_camera_trigger:
  195. break;
  196. case JSButton::button_function_t::k_camera_source_toggle:
  197. if (!held) {
  198. static bool video_toggle = false;
  199. video_toggle = !video_toggle;
  200. if (video_toggle) {
  201. video_switch = 1900;
  202. gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 2");
  203. } else {
  204. video_switch = 1100;
  205. gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 1");
  206. }
  207. }
  208. break;
  209. case JSButton::button_function_t::k_mount_pan_right:
  210. cam_pan = 1900;
  211. break;
  212. case JSButton::button_function_t::k_mount_pan_left:
  213. cam_pan = 1100;
  214. break;
  215. case JSButton::button_function_t::k_lights1_cycle:
  216. if (!held) {
  217. if(lights1 ==0){
  218. lights1 = 20000;
  219. //sub.lights = 1;
  220. }
  221. else{
  222. lights1 = 0;
  223. //sub.lights = 0;
  224. }
  225. }
  226. break;
  227. case JSButton::button_function_t::k_lights1_brighter:
  228. if (!held) {
  229. RC_Channel* chan = RC_Channels::rc_channel(8);
  230. uint16_t min = chan->get_radio_min();
  231. uint16_t max = chan->get_radio_max();
  232. uint16_t step = (max - min) / g.lights_steps;
  233. lights1 = constrain_float(lights1 + step, min, max);
  234. }
  235. break;
  236. case JSButton::button_function_t::k_lights1_dimmer:
  237. if (!held) {
  238. RC_Channel* chan = RC_Channels::rc_channel(8);
  239. uint16_t min = chan->get_radio_min();
  240. uint16_t max = chan->get_radio_max();
  241. uint16_t step = (max - min) / g.lights_steps;
  242. lights1 = constrain_float(lights1 - step, min, max);
  243. }
  244. break;
  245. case JSButton::button_function_t::k_lights2_cycle:
  246. if (!held) {
  247. if(lights2 ==0){
  248. lights2 = 20000;
  249. sub.usblpoweroff = 1;
  250. }
  251. else{
  252. lights2 = 0;
  253. sub.usblpoweroff = 0;
  254. }
  255. }
  256. break;
  257. case JSButton::button_function_t::k_lights2_brighter:
  258. if (!held) {
  259. RC_Channel* chan = RC_Channels::rc_channel(9);
  260. uint16_t min = chan->get_radio_min();
  261. uint16_t max = chan->get_radio_max();
  262. uint16_t step = (max - min) / g.lights_steps;
  263. lights2 = constrain_float(lights2 + step, min, max);
  264. }
  265. break;
  266. case JSButton::button_function_t::k_lights2_dimmer:
  267. if (!held) {
  268. RC_Channel* chan = RC_Channels::rc_channel(9);
  269. uint16_t min = chan->get_radio_min();
  270. uint16_t max = chan->get_radio_max();
  271. uint16_t step = (max - min) / g.lights_steps;
  272. lights2 = constrain_float(lights2 - step, min, max);
  273. }
  274. break;
  275. case JSButton::button_function_t::k_gain_toggle:
  276. if (!held) {
  277. static bool lowGain = false;
  278. lowGain = !lowGain;
  279. if (lowGain) {
  280. gain = 0.5f;
  281. } else {
  282. gain = 1.0f;
  283. }
  284. gcs().send_text(MAV_SEVERITY_INFO,"#Gain: %2.0f%%",(double)gain*100);
  285. }
  286. break;
  287. case JSButton::button_function_t::k_gain_inc:
  288. {
  289. if (!held) {
  290. if(control_mode == CLEAN)
  291. {
  292. turn_angle =-16.0;
  293. gcs().send_text(MAV_SEVERITY_INFO,"%f turn_angle",(float)turn_angle);
  294. }else if(control_mode == STABILIZE){
  295. if (!motors.armed()){
  296. //gcs().send_text(MAV_SEVERITY_INFO,"disarm used by current yaw is %f",(float)yaw_press);
  297. }
  298. else{
  299. //yaw_press +=3;
  300. //if(yaw_press>=360){
  301. // yaw_press-=360;
  302. //}
  303. //gcs().send_text(MAV_SEVERITY_INFO,"%d %f yaw++",(int)yaw_press,(float)yaw_press);
  304. }
  305. }
  306. }
  307. break;
  308. }
  309. case JSButton::button_function_t::k_gain_dec:
  310. {
  311. if (!held) {
  312. if(control_mode == CLEAN)
  313. {
  314. turn_angle =16.0;
  315. gcs().send_text(MAV_SEVERITY_INFO,"%f turn_angle",(float)turn_angle);
  316. }else if(control_mode == STABILIZE){
  317. if (!motors.armed()){
  318. // gcs().send_text(MAV_SEVERITY_INFO,"disarm used by current yaw is %f",(float)yaw_press);
  319. }
  320. else{
  321. // yaw_press -=3;
  322. // if(yaw_press<0){
  323. // yaw_press+=360;
  324. // }
  325. // gcs().send_text(MAV_SEVERITY_INFO,"%d %f yaw--",(int)yaw_press,(float)yaw_press);
  326. }
  327. }
  328. }
  329. break;
  330. }
  331. case JSButton::button_function_t::k_trim_roll_inc:
  332. attitudeTarget.rotate(localRoll * radians(1));
  333. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  334. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  335. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  336. break;
  337. case JSButton::button_function_t::k_trim_roll_dec:
  338. attitudeTarget.rotate(localRoll * radians(-1));
  339. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  340. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  341. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  342. break;
  343. case JSButton::button_function_t::k_trim_pitch_inc:
  344. attitudeTarget.rotate(localPitch * radians(1));
  345. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  346. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  347. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  348. break;
  349. case JSButton::button_function_t::k_trim_pitch_dec:
  350. attitudeTarget.rotate(localPitch * radians(-1));
  351. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  352. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  353. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  354. break;
  355. case JSButton::button_function_t::k_input_hold_set:
  356. if(!motors.armed()) {
  357. break;
  358. }
  359. if(roll_pitch_flag) {
  360. last_pitch = 0;
  361. last_roll = 0;
  362. last_input_ms = 0;
  363. break;
  364. }
  365. if (!held) {
  366. zTrim = abs(z_last-500) > 50 ? z_last-500 : 0;
  367. xTrim = abs(x_last) > 50 ? x_last : 0;
  368. yTrim = abs(y_last) > 50 ? y_last : 0;
  369. bool input_hold_engaged_last = input_hold_engaged;
  370. input_hold_engaged = zTrim || xTrim || yTrim;
  371. if (input_hold_engaged) {
  372. gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Set");
  373. } else if (input_hold_engaged_last) {
  374. gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Disabled");
  375. }
  376. controls_reset_since_input_hold = !input_hold_engaged;
  377. }
  378. break;
  379. case JSButton::button_function_t::k_relay_1_on:
  380. relay.on(0);
  381. break;
  382. case JSButton::button_function_t::k_relay_1_off:
  383. relay.off(0);
  384. break;
  385. case JSButton::button_function_t::k_relay_1_toggle:
  386. if (!held) {
  387. relay.toggle(0);
  388. }
  389. break;
  390. case JSButton::button_function_t::k_relay_1_momentary:
  391. if (!held) {
  392. relay.on(0);
  393. }
  394. break;
  395. case JSButton::button_function_t::k_relay_2_on:
  396. relay.on(1);
  397. break;
  398. case JSButton::button_function_t::k_relay_2_off:
  399. relay.off(1);
  400. break;
  401. case JSButton::button_function_t::k_relay_2_toggle:
  402. if (!held) {
  403. relay.toggle(1);
  404. }
  405. break;
  406. case JSButton::button_function_t::k_relay_2_momentary:
  407. if (!held) {
  408. relay.on(1);
  409. }
  410. break;
  411. case JSButton::button_function_t::k_relay_3_on:
  412. relay.on(2);
  413. break;
  414. case JSButton::button_function_t::k_relay_3_off:
  415. relay.off(2);
  416. break;
  417. case JSButton::button_function_t::k_relay_3_toggle:
  418. if (!held) {
  419. relay.toggle(2);
  420. }
  421. break;
  422. case JSButton::button_function_t::k_relay_3_momentary:
  423. if (!held) {
  424. relay.on(2);
  425. }
  426. break;
  427. case JSButton::button_function_t::k_relay_4_on:
  428. relay.on(3);
  429. break;
  430. case JSButton::button_function_t::k_relay_4_off:
  431. relay.off(3);
  432. break;
  433. case JSButton::button_function_t::k_relay_4_toggle:
  434. if (!held) {
  435. relay.toggle(3);
  436. }
  437. break;
  438. case JSButton::button_function_t::k_relay_4_momentary:
  439. if (!held) {
  440. relay.on(3);
  441. }
  442. break;
  443. ////////////////////////////////////////////////
  444. // Servo functions
  445. // TODO: initialize
  446. case JSButton::button_function_t::k_servo_1_inc:
  447. {
  448. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  449. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
  450. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  451. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
  452. }
  453. break;
  454. case JSButton::button_function_t::k_servo_1_dec:
  455. {
  456. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  457. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
  458. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  459. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
  460. }
  461. break;
  462. case JSButton::button_function_t::k_servo_1_min:
  463. case JSButton::button_function_t::k_servo_1_min_momentary:
  464. {
  465. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  466. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
  467. }
  468. break;
  469. case JSButton::button_function_t::k_servo_1_min_toggle:
  470. if(!held) {
  471. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  472. if(chan->get_output_pwm() != chan->get_output_min()) {
  473. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
  474. } else {
  475. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  476. }
  477. }
  478. break;
  479. case JSButton::button_function_t::k_servo_1_max:
  480. case JSButton::button_function_t::k_servo_1_max_momentary:
  481. {
  482. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  483. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
  484. }
  485. break;
  486. case JSButton::button_function_t::k_servo_1_max_toggle:
  487. if(!held) {
  488. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  489. if(chan->get_output_pwm() != chan->get_output_max()) {
  490. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
  491. } else {
  492. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  493. }
  494. }
  495. break;
  496. case JSButton::button_function_t::k_servo_1_center:
  497. {
  498. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  499. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  500. }
  501. break;
  502. case JSButton::button_function_t::k_servo_2_inc:
  503. {
  504. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  505. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
  506. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  507. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
  508. }
  509. break;
  510. case JSButton::button_function_t::k_servo_2_dec:
  511. {
  512. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  513. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
  514. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  515. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
  516. }
  517. break;
  518. case JSButton::button_function_t::k_servo_2_min:
  519. case JSButton::button_function_t::k_servo_2_min_momentary:
  520. {
  521. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  522. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
  523. }
  524. break;
  525. case JSButton::button_function_t::k_servo_2_max:
  526. case JSButton::button_function_t::k_servo_2_max_momentary:
  527. {
  528. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  529. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
  530. }
  531. break;
  532. case JSButton::button_function_t::k_servo_2_center:
  533. {
  534. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  535. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
  536. }
  537. break;
  538. case JSButton::button_function_t::k_servo_3_inc:
  539. {
  540. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  541. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
  542. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  543. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
  544. }
  545. break;
  546. case JSButton::button_function_t::k_servo_3_dec:
  547. {
  548. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  549. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
  550. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  551. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
  552. }
  553. break;
  554. case JSButton::button_function_t::k_servo_3_min:
  555. case JSButton::button_function_t::k_servo_3_min_momentary:
  556. {
  557. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  558. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
  559. }
  560. break;
  561. case JSButton::button_function_t::k_servo_3_max:
  562. case JSButton::button_function_t::k_servo_3_max_momentary:
  563. {
  564. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  565. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
  566. }
  567. break;
  568. case JSButton::button_function_t::k_servo_3_center:
  569. {
  570. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  571. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
  572. }
  573. break;
  574. case JSButton::button_function_t::k_roll_pitch_toggle:
  575. if (!held) {
  576. roll_pitch_flag = !roll_pitch_flag;
  577. }
  578. break;
  579. case JSButton::button_function_t::k_custom_1:
  580. if (!held)
  581. {
  582. if(control_mode == STABILIZE){
  583. //水平和竖直切换
  584. if (prepare_state == Horizontal)
  585. {
  586. prepare_state = Vertical;
  587. track_head_gd =0.0;
  588. }
  589. else if (prepare_state == Vertical)
  590. {
  591. prepare_state = Horizontal;
  592. }
  593. gcs().send_text(MAV_SEVERITY_INFO,"prepare_state: %d",(int)prepare_state);
  594. }
  595. else if(control_mode == ACRO){
  596. if(autoclean_command == FALSE){
  597. autoclean_command =TRUE;
  598. }else{
  599. autoclean_command =FALSE;
  600. }
  601. gcs().send_text(MAV_SEVERITY_INFO,"autoclean_flag: %d",(int)autoclean_command);
  602. }
  603. }
  604. break;
  605. case JSButton::button_function_t::k_custom_2:
  606. if (!held) {
  607. //十级
  608. if(PressLevel == first)
  609. {
  610. PressLevel = second;
  611. PressLevel_f = 0.5;//
  612. }else if(PressLevel == second){
  613. PressLevel = third;
  614. PressLevel_f = 1.0;//
  615. }else if(PressLevel == third){
  616. PressLevel = forth;
  617. PressLevel_f = 1.8;//
  618. }else if (PressLevel == forth){
  619. PressLevel = fifth;
  620. PressLevel_f = 4.5;
  621. }else if(PressLevel == fifth){
  622. PressLevel = no;
  623. PressLevel_f = 5.0; //
  624. }else if(PressLevel == no){
  625. PressLevel = sixth;
  626. PressLevel_f = 5.5;
  627. }else if (PressLevel == sixth){
  628. PressLevel = seventh;
  629. PressLevel_f = 8.2;
  630. }else if(PressLevel == seventh){
  631. PressLevel = eighth;
  632. PressLevel_f = 9.0;
  633. }else if (PressLevel == eighth){
  634. PressLevel = ninth;
  635. PressLevel_f = 9.5;
  636. }else if (PressLevel == ninth){
  637. PressLevel = tenth;
  638. PressLevel_f = 10.0;
  639. }else{
  640. PressLevel = tenth;
  641. PressLevel_f = 10.0;
  642. }
  643. gcs().send_text(MAV_SEVERITY_INFO,"%f level",(float)PressLevel_f);
  644. }
  645. break;
  646. case JSButton::button_function_t::k_custom_3:
  647. if (!held)
  648. {//十级
  649. if(PressLevel == tenth)
  650. {
  651. PressLevel = ninth;
  652. PressLevel_f = 9.5;//8.9
  653. }else if(PressLevel == ninth) {
  654. PressLevel = eighth;
  655. PressLevel_f = 9.0;//8.6
  656. }else if(PressLevel == eighth){
  657. PressLevel = seventh;
  658. PressLevel_f = 8.2;//8.2
  659. }else if (PressLevel == seventh){
  660. PressLevel = sixth;
  661. PressLevel_f = 5.5;//7.5
  662. }else if(PressLevel == sixth){
  663. PressLevel = no;
  664. PressLevel_f = 5.0;//5.0
  665. }else if(PressLevel == no){
  666. PressLevel = fifth;
  667. PressLevel_f = 4.5; //2.5
  668. }else if (PressLevel == fifth){
  669. PressLevel = forth;
  670. PressLevel_f = 1.8;//1.8
  671. }else if(PressLevel == forth){
  672. PressLevel = third;
  673. PressLevel_f = 1.0;//1.4
  674. }else if (PressLevel == third){
  675. PressLevel = second;
  676. PressLevel_f = 0.5; //1.1
  677. }else if (PressLevel == second){
  678. PressLevel = first;
  679. PressLevel_f = 0.0;//0.9
  680. }else{
  681. PressLevel = first;
  682. PressLevel_f = 0.0; //0.9
  683. }
  684. gcs().send_text(MAV_SEVERITY_INFO,"%f level",(float)PressLevel_f);
  685. }
  686. break;
  687. case JSButton::button_function_t::k_custom_4:
  688. // Not implemented
  689. break;
  690. case JSButton::button_function_t::k_custom_5:
  691. // Not implemented
  692. break;
  693. case JSButton::button_function_t::k_custom_6:
  694. if (!held){
  695. if(clean_mode == 0){
  696. clean_mode =1;
  697. }else{
  698. clean_mode =0;
  699. }
  700. }
  701. break;
  702. }
  703. }
  704. void Sub::handle_jsbutton_release(uint8_t button, bool shift) {
  705. // Act based on the function assigned to this button
  706. switch (get_button(button)->function(shift)) {
  707. case JSButton::button_function_t::k_relay_1_momentary:
  708. relay.off(0);
  709. break;
  710. case JSButton::button_function_t::k_relay_2_momentary:
  711. relay.off(1);
  712. break;
  713. case JSButton::button_function_t::k_relay_3_momentary:
  714. relay.off(2);
  715. break;
  716. case JSButton::button_function_t::k_relay_4_momentary:
  717. relay.off(3);
  718. break;
  719. case JSButton::button_function_t::k_servo_1_min_momentary:
  720. case JSButton::button_function_t::k_servo_1_max_momentary:
  721. {
  722. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  723. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  724. }
  725. break;
  726. case JSButton::button_function_t::k_servo_2_min_momentary:
  727. case JSButton::button_function_t::k_servo_2_max_momentary:
  728. {
  729. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  730. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
  731. }
  732. break;
  733. case JSButton::button_function_t::k_servo_3_min_momentary:
  734. case JSButton::button_function_t::k_servo_3_max_momentary:
  735. {
  736. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  737. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
  738. }
  739. break;
  740. }
  741. }
  742. JSButton* Sub::get_button(uint8_t index)
  743. {
  744. // Help to access appropriate parameter
  745. switch (index) {
  746. case 0:
  747. return &g.jbtn_0;
  748. case 1:
  749. return &g.jbtn_1;
  750. case 2:
  751. return &g.jbtn_2;
  752. case 3:
  753. return &g.jbtn_3;
  754. case 4:
  755. return &g.jbtn_4;
  756. case 5:
  757. return &g.jbtn_5;
  758. case 6:
  759. return &g.jbtn_6;
  760. case 7:
  761. return &g.jbtn_7;
  762. case 8:
  763. return &g.jbtn_8;
  764. case 9:
  765. return &g.jbtn_9;
  766. case 10:
  767. return &g.jbtn_10;
  768. case 11:
  769. return &g.jbtn_11;
  770. case 12:
  771. return &g.jbtn_12;
  772. case 13:
  773. return &g.jbtn_13;
  774. case 14:
  775. return &g.jbtn_14;
  776. case 15:
  777. return &g.jbtn_15;
  778. default:
  779. return &g.jbtn_0;
  780. }
  781. }
  782. void Sub::default_js_buttons()
  783. {
  784. JSButton::button_function_t defaults[16][2] = {
  785. {JSButton::button_function_t::k_mode_clean, JSButton::button_function_t::k_none},
  786. {JSButton::button_function_t::k_mode_manual, JSButton::button_function_t::k_none},
  787. {JSButton::button_function_t::k_mode_depth_hold, JSButton::button_function_t::k_none},
  788. {JSButton::button_function_t::k_mode_stabilize, JSButton::button_function_t::k_none},
  789. {JSButton::button_function_t::k_disarm, JSButton::button_function_t::k_none},
  790. {JSButton::button_function_t::k_shift, JSButton::button_function_t::k_none},
  791. {JSButton::button_function_t::k_arm, JSButton::button_function_t::k_none},
  792. {JSButton::button_function_t::k_mount_center, JSButton::button_function_t::k_none},
  793. {JSButton::button_function_t::k_input_hold_set, JSButton::button_function_t::k_none},
  794. {JSButton::button_function_t::k_mount_tilt_down, JSButton::button_function_t::k_mount_pan_left},
  795. {JSButton::button_function_t::k_mount_tilt_up, JSButton::button_function_t::k_mount_pan_right},
  796. {JSButton::button_function_t::k_gain_inc, JSButton::button_function_t::k_trim_pitch_dec},
  797. {JSButton::button_function_t::k_gain_dec, JSButton::button_function_t::k_trim_pitch_inc},
  798. {JSButton::button_function_t::k_lights1_dimmer, JSButton::button_function_t::k_trim_roll_dec},
  799. {JSButton::button_function_t::k_lights1_brighter, JSButton::button_function_t::k_trim_roll_inc},
  800. {JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
  801. };
  802. for (int i = 0; i < 16; i++) {
  803. get_button(i)->set_default(defaults[i][0], defaults[i][1]);
  804. }
  805. }
  806. void Sub::set_neutral_controls()
  807. {
  808. uint32_t tnow = AP_HAL::millis();
  809. for (uint8_t i = 0; i < 6; i++) {
  810. RC_Channels::set_override(i, 1500, tnow);
  811. }
  812. // Clear pitch/roll trim settings
  813. pitchTrim = 0;
  814. rollTrim = 0;
  815. }
  816. void Sub::clear_input_hold()
  817. {
  818. xTrim = 0;
  819. yTrim = 0;
  820. zTrim = 0;
  821. input_hold_engaged = false;
  822. }