joystick.cpp 29 KB

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