joystick.cpp 30 KB

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