joystick.cpp 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865
  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 lights2 = 0;
  9. int16_t rollTrim = 0;
  10. int16_t pitchTrim = 0;
  11. int16_t zTrim = 0;
  12. int16_t xTrim = 0;
  13. int16_t yTrim = 0;
  14. int16_t video_switch = 1100;
  15. int16_t x_last, y_last, z_last;
  16. uint16_t buttons_prev;
  17. // Servo control output channels
  18. // TODO: Allow selecting output channels
  19. const uint8_t SERVO_CHAN_1 = 9; // Pixhawk Aux1
  20. const uint8_t SERVO_CHAN_2 = 10; // Pixhawk Aux2
  21. const uint8_t SERVO_CHAN_3 = 11; // Pixhawk Aux3
  22. uint8_t roll_pitch_flag = false; // Flag to adjust roll/pitch instead of forward/lateral
  23. bool controls_reset_since_input_hold = true;
  24. }
  25. void Sub::init_joystick()
  26. {
  27. default_js_buttons();
  28. lights1 = 0;
  29. lights2 = 0;
  30. set_mode(MANUAL, MODE_REASON_TX_COMMAND); // Initialize flight mode
  31. if (g.numGainSettings < 1) {
  32. g.numGainSettings.set_and_save(1);
  33. }
  34. if (g.numGainSettings == 1 || (g.gain_default < g.maxGain + 0.01 && g.gain_default > g.minGain - 0.01)) {
  35. gain = constrain_float(g.gain_default, g.minGain, g.maxGain); // Use default gain parameter
  36. } else {
  37. // Use setting closest to average of minGain and maxGain
  38. gain = g.minGain + (g.numGainSettings/2 - 1) * (g.maxGain - g.minGain) / (g.numGainSettings - 1);
  39. }
  40. gain = constrain_float(gain, 0.1, 1.0);
  41. }
  42. extern mavlink_rov_control_t rov_control;
  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. RC_Channel* chan = RC_Channels::rc_channel(8);
  218. uint16_t min = chan->get_radio_min();
  219. uint16_t max = chan->get_radio_max();
  220. if(lights1 ==min){
  221. lights1 = constrain_float(max, min, max);
  222. }
  223. else{
  224. lights1 = constrain_float(min, min, max);
  225. }
  226. gcs().send_text(MAV_SEVERITY_INFO,"min %d %d",rov_control.floodlight,lights1);
  227. }
  228. break;
  229. case JSButton::button_function_t::k_lights1_brighter:
  230. if (!held) {
  231. RC_Channel* chan = RC_Channels::rc_channel(8);
  232. uint16_t min = chan->get_radio_min();
  233. uint16_t max = chan->get_radio_max();
  234. uint16_t step = (max - min) / g.lights_steps;
  235. lights1 = constrain_float(lights1 + step, min, max);
  236. }
  237. break;
  238. case JSButton::button_function_t::k_lights1_dimmer:
  239. if (!held) {
  240. RC_Channel* chan = RC_Channels::rc_channel(8);
  241. uint16_t min = chan->get_radio_min();
  242. uint16_t max = chan->get_radio_max();
  243. uint16_t step = (max - min) / g.lights_steps;
  244. lights1 = constrain_float(lights1 - step, min, max);
  245. }
  246. break;
  247. case JSButton::button_function_t::k_lights2_cycle:
  248. if (!held) {
  249. if(lights2 ==0){
  250. lights2 = 20000;
  251. sub.usblpoweroff = 1;
  252. }
  253. else{
  254. lights2 = 0;
  255. sub.usblpoweroff = 0;
  256. }
  257. }
  258. break;
  259. case JSButton::button_function_t::k_lights2_brighter:
  260. if (!held) {
  261. RC_Channel* chan = RC_Channels::rc_channel(9);
  262. uint16_t min = chan->get_radio_min();
  263. uint16_t max = chan->get_radio_max();
  264. uint16_t step = (max - min) / g.lights_steps;
  265. lights2 = constrain_float(lights2 + step, min, max);
  266. }
  267. break;
  268. case JSButton::button_function_t::k_lights2_dimmer:
  269. if (!held) {
  270. RC_Channel* chan = RC_Channels::rc_channel(9);
  271. uint16_t min = chan->get_radio_min();
  272. uint16_t max = chan->get_radio_max();
  273. uint16_t step = (max - min) / g.lights_steps;
  274. lights2 = constrain_float(lights2 - step, min, max);
  275. }
  276. break;
  277. case JSButton::button_function_t::k_gain_toggle:
  278. if (!held) {
  279. static bool lowGain = false;
  280. lowGain = !lowGain;
  281. if (lowGain) {
  282. gain = 0.5f;
  283. } else {
  284. gain = 1.0f;
  285. }
  286. gcs().send_text(MAV_SEVERITY_INFO,"#Gain: %2.0f%%",(double)gain*100);
  287. }
  288. break;
  289. case JSButton::button_function_t::k_gain_inc:
  290. {
  291. {
  292. updowmgain=0.3;//下
  293. delaygain =0;
  294. }
  295. break;
  296. }
  297. case JSButton::button_function_t::k_gain_dec:
  298. {
  299. {
  300. updowmgain=0.7;
  301. delaygain =0;
  302. }
  303. break;
  304. }
  305. case JSButton::button_function_t::k_trim_roll_inc:
  306. attitudeTarget.rotate(localRoll * radians(1));
  307. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  308. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  309. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  310. break;
  311. case JSButton::button_function_t::k_trim_roll_dec:
  312. attitudeTarget.rotate(localRoll * radians(-1));
  313. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  314. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  315. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  316. break;
  317. case JSButton::button_function_t::k_trim_pitch_inc:
  318. attitudeTarget.rotate(localPitch * radians(1));
  319. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  320. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  321. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  322. break;
  323. case JSButton::button_function_t::k_trim_pitch_dec:
  324. attitudeTarget.rotate(localPitch * radians(-1));
  325. last_roll = degrees(attitudeTarget.get_euler_roll()) * 100;
  326. last_pitch = degrees(attitudeTarget.get_euler_pitch()) * 100;
  327. last_yaw = degrees(attitudeTarget.get_euler_yaw()) * 100;
  328. break;
  329. case JSButton::button_function_t::k_input_hold_set:
  330. if(!motors.armed()) {
  331. break;
  332. }
  333. if(roll_pitch_flag) {
  334. last_pitch = 0;
  335. last_roll = 0;
  336. last_input_ms = 0;
  337. break;
  338. }
  339. if (!held) {
  340. zTrim = abs(z_last-500) > 50 ? z_last-500 : 0;
  341. xTrim = abs(x_last) > 50 ? x_last : 0;
  342. yTrim = abs(y_last) > 50 ? y_last : 0;
  343. bool input_hold_engaged_last = input_hold_engaged;
  344. input_hold_engaged = zTrim || xTrim || yTrim;
  345. if (input_hold_engaged) {
  346. gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Set");
  347. } else if (input_hold_engaged_last) {
  348. gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Disabled");
  349. }
  350. controls_reset_since_input_hold = !input_hold_engaged;
  351. }
  352. break;
  353. case JSButton::button_function_t::k_relay_1_on:
  354. relay.on(0);
  355. break;
  356. case JSButton::button_function_t::k_relay_1_off:
  357. relay.off(0);
  358. break;
  359. case JSButton::button_function_t::k_relay_1_toggle:
  360. if (!held) {
  361. relay.toggle(0);
  362. }
  363. break;
  364. case JSButton::button_function_t::k_relay_1_momentary:
  365. if (!held) {
  366. relay.on(0);
  367. }
  368. break;
  369. case JSButton::button_function_t::k_relay_2_on:
  370. relay.on(1);
  371. break;
  372. case JSButton::button_function_t::k_relay_2_off:
  373. relay.off(1);
  374. break;
  375. case JSButton::button_function_t::k_relay_2_toggle:
  376. if (!held) {
  377. relay.toggle(1);
  378. }
  379. break;
  380. case JSButton::button_function_t::k_relay_2_momentary:
  381. if (!held) {
  382. relay.on(1);
  383. }
  384. break;
  385. case JSButton::button_function_t::k_relay_3_on:
  386. relay.on(2);
  387. break;
  388. case JSButton::button_function_t::k_relay_3_off:
  389. relay.off(2);
  390. break;
  391. case JSButton::button_function_t::k_relay_3_toggle:
  392. if (!held) {
  393. relay.toggle(2);
  394. }
  395. break;
  396. case JSButton::button_function_t::k_relay_3_momentary:
  397. if (!held) {
  398. relay.on(2);
  399. }
  400. break;
  401. case JSButton::button_function_t::k_relay_4_on:
  402. relay.on(3);
  403. break;
  404. case JSButton::button_function_t::k_relay_4_off:
  405. relay.off(3);
  406. break;
  407. case JSButton::button_function_t::k_relay_4_toggle:
  408. if (!held) {
  409. relay.toggle(3);
  410. }
  411. break;
  412. case JSButton::button_function_t::k_relay_4_momentary:
  413. if (!held) {
  414. relay.on(3);
  415. }
  416. break;
  417. ////////////////////////////////////////////////
  418. // Servo functions
  419. // TODO: initialize
  420. case JSButton::button_function_t::k_servo_1_inc:
  421. {
  422. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  423. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
  424. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  425. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
  426. }
  427. break;
  428. case JSButton::button_function_t::k_servo_1_dec:
  429. {
  430. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  431. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
  432. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  433. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
  434. }
  435. break;
  436. case JSButton::button_function_t::k_servo_1_min:
  437. case JSButton::button_function_t::k_servo_1_min_momentary:
  438. {
  439. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  440. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
  441. }
  442. break;
  443. case JSButton::button_function_t::k_servo_1_min_toggle:
  444. if(!held) {
  445. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  446. if(chan->get_output_pwm() != chan->get_output_min()) {
  447. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
  448. } else {
  449. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  450. }
  451. }
  452. break;
  453. case JSButton::button_function_t::k_servo_1_max:
  454. case JSButton::button_function_t::k_servo_1_max_momentary:
  455. {
  456. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  457. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
  458. }
  459. break;
  460. case JSButton::button_function_t::k_servo_1_max_toggle:
  461. if(!held) {
  462. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  463. if(chan->get_output_pwm() != chan->get_output_max()) {
  464. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
  465. } else {
  466. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  467. }
  468. }
  469. break;
  470. case JSButton::button_function_t::k_servo_1_center:
  471. {
  472. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  473. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  474. }
  475. break;
  476. case JSButton::button_function_t::k_servo_2_inc:
  477. {
  478. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  479. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
  480. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  481. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
  482. }
  483. break;
  484. case JSButton::button_function_t::k_servo_2_dec:
  485. {
  486. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  487. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
  488. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  489. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
  490. }
  491. break;
  492. case JSButton::button_function_t::k_servo_2_min:
  493. case JSButton::button_function_t::k_servo_2_min_momentary:
  494. {
  495. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  496. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
  497. }
  498. break;
  499. case JSButton::button_function_t::k_servo_2_max:
  500. case JSButton::button_function_t::k_servo_2_max_momentary:
  501. {
  502. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  503. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
  504. }
  505. break;
  506. case JSButton::button_function_t::k_servo_2_center:
  507. {
  508. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  509. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
  510. }
  511. break;
  512. case JSButton::button_function_t::k_servo_3_inc:
  513. {
  514. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  515. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
  516. pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
  517. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
  518. }
  519. break;
  520. case JSButton::button_function_t::k_servo_3_dec:
  521. {
  522. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  523. uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
  524. pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
  525. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
  526. }
  527. break;
  528. case JSButton::button_function_t::k_servo_3_min:
  529. case JSButton::button_function_t::k_servo_3_min_momentary:
  530. {
  531. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  532. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
  533. }
  534. break;
  535. case JSButton::button_function_t::k_servo_3_max:
  536. case JSButton::button_function_t::k_servo_3_max_momentary:
  537. {
  538. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  539. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
  540. }
  541. break;
  542. case JSButton::button_function_t::k_servo_3_center:
  543. {
  544. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  545. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
  546. }
  547. break;
  548. case JSButton::button_function_t::k_roll_pitch_toggle:
  549. if (!held) {
  550. roll_pitch_flag = !roll_pitch_flag;
  551. }
  552. break;
  553. case JSButton::button_function_t::k_custom_1:
  554. if (!held)
  555. {
  556. if(control_mode == STABILIZE){
  557. //水平和竖直切换
  558. if (prepare_state == Horizontal)
  559. {
  560. prepare_state = Vertical;
  561. track_head_gd =0.0;
  562. }
  563. else if (prepare_state == Vertical)
  564. {
  565. prepare_state = Horizontal;
  566. }
  567. gcs().send_text(MAV_SEVERITY_INFO,"prepare_state: %d",(int)prepare_state);
  568. }
  569. else if(control_mode == ACRO){
  570. if(autoclean_command == FALSE){
  571. autoclean_command =TRUE;
  572. }else{
  573. autoclean_command =FALSE;
  574. }
  575. gcs().send_text(MAV_SEVERITY_INFO,"autoclean_flag: %d",(int)autoclean_command);
  576. }
  577. }
  578. break;
  579. case JSButton::button_function_t::k_custom_2:
  580. if (!held) {
  581. //十级
  582. if(PressLevel == first)
  583. {
  584. PressLevel = second;
  585. PressLevel_f = 0.5;//
  586. }else if(PressLevel == second){
  587. PressLevel = third;
  588. PressLevel_f = 1.0;//
  589. }else if(PressLevel == third){
  590. PressLevel = forth;
  591. PressLevel_f = 1.8;//
  592. }else if (PressLevel == forth){
  593. PressLevel = fifth;
  594. PressLevel_f = 4.5;
  595. }else if(PressLevel == fifth){
  596. PressLevel = no;
  597. PressLevel_f = 5.0; //
  598. }else if(PressLevel == no){
  599. PressLevel = sixth;
  600. PressLevel_f = 5.5;
  601. }else if (PressLevel == sixth){
  602. PressLevel = seventh;
  603. PressLevel_f = 8.2;
  604. }else if(PressLevel == seventh){
  605. PressLevel = eighth;
  606. PressLevel_f = 9.0;
  607. }else if (PressLevel == eighth){
  608. PressLevel = ninth;
  609. PressLevel_f = 9.5;
  610. }else if (PressLevel == ninth){
  611. PressLevel = tenth;
  612. PressLevel_f = 10.0;
  613. }else{
  614. PressLevel = tenth;
  615. PressLevel_f = 10.0;
  616. }
  617. gcs().send_text(MAV_SEVERITY_INFO,"%f level",(float)PressLevel_f);
  618. }
  619. break;
  620. case JSButton::button_function_t::k_custom_3:
  621. if (!held)
  622. {//十级
  623. if(PressLevel == tenth)
  624. {
  625. PressLevel = ninth;
  626. PressLevel_f = 9.5;//8.9
  627. }else if(PressLevel == ninth) {
  628. PressLevel = eighth;
  629. PressLevel_f = 9.0;//8.6
  630. }else if(PressLevel == eighth){
  631. PressLevel = seventh;
  632. PressLevel_f = 8.2;//8.2
  633. }else if (PressLevel == seventh){
  634. PressLevel = sixth;
  635. PressLevel_f = 5.5;//7.5
  636. }else if(PressLevel == sixth){
  637. PressLevel = no;
  638. PressLevel_f = 5.0;//5.0
  639. }else if(PressLevel == no){
  640. PressLevel = fifth;
  641. PressLevel_f = 4.5; //2.5
  642. }else if (PressLevel == fifth){
  643. PressLevel = forth;
  644. PressLevel_f = 1.8;//1.8
  645. }else if(PressLevel == forth){
  646. PressLevel = third;
  647. PressLevel_f = 1.0;//1.4
  648. }else if (PressLevel == third){
  649. PressLevel = second;
  650. PressLevel_f = 0.5; //1.1
  651. }else if (PressLevel == second){
  652. PressLevel = first;
  653. PressLevel_f = 0.0;//0.9
  654. }else{
  655. PressLevel = first;
  656. PressLevel_f = 0.0; //0.9
  657. }
  658. gcs().send_text(MAV_SEVERITY_INFO,"%f level",(float)PressLevel_f);
  659. }
  660. break;
  661. case JSButton::button_function_t::k_custom_4:
  662. // Not implemented
  663. break;
  664. case JSButton::button_function_t::k_custom_5:
  665. // Not implemented
  666. break;
  667. case JSButton::button_function_t::k_custom_6:
  668. if (!held){
  669. if(clean_mode == 0){
  670. clean_mode =1;
  671. }else{
  672. clean_mode =0;
  673. }
  674. }
  675. break;
  676. }
  677. }
  678. void Sub::handle_jsbutton_release(uint8_t button, bool shift) {
  679. // Act based on the function assigned to this button
  680. switch (get_button(button)->function(shift)) {
  681. case JSButton::button_function_t::k_relay_1_momentary:
  682. relay.off(0);
  683. break;
  684. case JSButton::button_function_t::k_relay_2_momentary:
  685. relay.off(1);
  686. break;
  687. case JSButton::button_function_t::k_relay_3_momentary:
  688. relay.off(2);
  689. break;
  690. case JSButton::button_function_t::k_relay_4_momentary:
  691. relay.off(3);
  692. break;
  693. case JSButton::button_function_t::k_servo_1_min_momentary:
  694. case JSButton::button_function_t::k_servo_1_max_momentary:
  695. {
  696. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
  697. ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
  698. }
  699. break;
  700. case JSButton::button_function_t::k_servo_2_min_momentary:
  701. case JSButton::button_function_t::k_servo_2_max_momentary:
  702. {
  703. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
  704. ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
  705. }
  706. break;
  707. case JSButton::button_function_t::k_servo_3_min_momentary:
  708. case JSButton::button_function_t::k_servo_3_max_momentary:
  709. {
  710. SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
  711. ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
  712. }
  713. break;
  714. }
  715. }
  716. JSButton* Sub::get_button(uint8_t index)
  717. {
  718. // Help to access appropriate parameter
  719. switch (index) {
  720. case 0:
  721. return &g.jbtn_0;
  722. case 1:
  723. return &g.jbtn_1;
  724. case 2:
  725. return &g.jbtn_2;
  726. case 3:
  727. return &g.jbtn_3;
  728. case 4:
  729. return &g.jbtn_4;
  730. case 5:
  731. return &g.jbtn_5;
  732. case 6:
  733. return &g.jbtn_6;
  734. case 7:
  735. return &g.jbtn_7;
  736. case 8:
  737. return &g.jbtn_8;
  738. case 9:
  739. return &g.jbtn_9;
  740. case 10:
  741. return &g.jbtn_10;
  742. case 11:
  743. return &g.jbtn_11;
  744. case 12:
  745. return &g.jbtn_12;
  746. case 13:
  747. return &g.jbtn_13;
  748. case 14:
  749. return &g.jbtn_14;
  750. case 15:
  751. return &g.jbtn_15;
  752. default:
  753. return &g.jbtn_0;
  754. }
  755. }
  756. void Sub::default_js_buttons()
  757. {
  758. JSButton::button_function_t defaults[16][2] = {
  759. {JSButton::button_function_t::k_mode_clean, JSButton::button_function_t::k_none},
  760. {JSButton::button_function_t::k_mode_manual, JSButton::button_function_t::k_none},
  761. {JSButton::button_function_t::k_mode_depth_hold, JSButton::button_function_t::k_none},
  762. {JSButton::button_function_t::k_mode_stabilize, JSButton::button_function_t::k_none},
  763. {JSButton::button_function_t::k_disarm, JSButton::button_function_t::k_none},
  764. {JSButton::button_function_t::k_shift, JSButton::button_function_t::k_none},
  765. {JSButton::button_function_t::k_arm, JSButton::button_function_t::k_none},
  766. {JSButton::button_function_t::k_mount_center, JSButton::button_function_t::k_none},
  767. {JSButton::button_function_t::k_input_hold_set, JSButton::button_function_t::k_none},
  768. {JSButton::button_function_t::k_mount_tilt_down, JSButton::button_function_t::k_mount_pan_left},
  769. {JSButton::button_function_t::k_mount_tilt_up, JSButton::button_function_t::k_mount_pan_right},
  770. {JSButton::button_function_t::k_gain_inc, JSButton::button_function_t::k_trim_pitch_dec},
  771. {JSButton::button_function_t::k_gain_dec, JSButton::button_function_t::k_trim_pitch_inc},
  772. {JSButton::button_function_t::k_lights1_dimmer, JSButton::button_function_t::k_trim_roll_dec},
  773. {JSButton::button_function_t::k_lights1_brighter, JSButton::button_function_t::k_trim_roll_inc},
  774. {JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
  775. };
  776. for (int i = 0; i < 16; i++) {
  777. get_button(i)->set_default(defaults[i][0], defaults[i][1]);
  778. }
  779. }
  780. void Sub::set_neutral_controls()
  781. {
  782. uint32_t tnow = AP_HAL::millis();
  783. for (uint8_t i = 0; i < 6; i++) {
  784. RC_Channels::set_override(i, 1500, tnow);
  785. }
  786. // Clear pitch/roll trim settings
  787. pitchTrim = 0;
  788. rollTrim = 0;
  789. }
  790. void Sub::clear_input_hold()
  791. {
  792. xTrim = 0;
  793. yTrim = 0;
  794. zTrim = 0;
  795. input_hold_engaged = false;
  796. }