joystick.cpp 30 KB

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