GCS_Mavlink.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918
  1. #include "Sub.h"
  2. #include "GCS_Mavlink.h"
  3. /*
  4. * !!NOTE!!
  5. *
  6. * the use of NOINLINE separate functions for each message type avoids
  7. * a compiler bug in gcc that would cause it to use far more stack
  8. * space than is needed. Without the NOINLINE we use the sum of the
  9. * stack needed for each message type. Please be careful to follow the
  10. * pattern below when adding any new messages
  11. */
  12. MAV_TYPE GCS_Sub::frame_type() const
  13. {
  14. return MAV_TYPE_SUBMARINE;
  15. }
  16. MAV_MODE GCS_MAVLINK_Sub::base_mode() const
  17. {
  18. uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
  19. // work out the base_mode. This value is not very useful
  20. // for APM, but we calculate it as best we can so a generic
  21. // MAVLink enabled ground station can work out something about
  22. // what the MAV is up to. The actual bit values are highly
  23. // ambiguous for most of the APM flight modes. In practice, you
  24. // only get useful information from the custom_mode, which maps to
  25. // the APM flight mode and has a well defined meaning in the
  26. // ArduPlane documentation
  27. switch (sub.control_mode) {
  28. case AUTO:
  29. case GUIDED:
  30. case CIRCLE:
  31. case POSHOLD:
  32. _base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
  33. // note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
  34. // APM does in any mode, as that is defined as "system finds its own goal
  35. // positions", which APM does not currently do
  36. break;
  37. default:
  38. break;
  39. }
  40. // all modes except INITIALISING have some form of manual
  41. // override if stick mixing is enabled
  42. _base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
  43. if (sub.motors.armed()) {
  44. _base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
  45. }
  46. // indicate we have set a custom mode
  47. _base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
  48. return (MAV_MODE)_base_mode;
  49. }
  50. uint32_t GCS_Sub::custom_mode() const
  51. {
  52. return sub.control_mode;
  53. }
  54. MAV_STATE GCS_MAVLINK_Sub::system_status() const
  55. {
  56. // set system as critical if any failsafe have triggered
  57. if (sub.any_failsafe_triggered()) {
  58. return MAV_STATE_CRITICAL;
  59. }
  60. if (sub.motors.armed()) {
  61. return MAV_STATE_ACTIVE;
  62. }
  63. return MAV_STATE_STANDBY;
  64. }
  65. void GCS_MAVLINK_Sub::send_nav_controller_output() const
  66. {
  67. const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();
  68. mavlink_msg_nav_controller_output_send(
  69. chan,
  70. targets.x * 1.0e-2f,
  71. targets.y * 1.0e-2f,
  72. targets.z * 1.0e-2f,
  73. sub.wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,
  74. MIN(sub.wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),
  75. sub.pos_control.get_alt_error() * 1.0e-2f,
  76. 0,
  77. 0);
  78. }
  79. int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
  80. {
  81. return (int16_t)(sub.motors.get_throttle() * 100);
  82. }
  83. // Work around to get temperature sensor data out
  84. void GCS_MAVLINK_Sub::send_scaled_pressure3()
  85. {
  86. if (!sub.celsius.healthy()) {
  87. return;
  88. }
  89. mavlink_msg_scaled_pressure3_send(
  90. chan,
  91. AP_HAL::millis(),
  92. 0,
  93. 0,
  94. sub.celsius.temperature() * 100);
  95. }
  96. bool GCS_MAVLINK_Sub::send_info()
  97. {
  98. // Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok
  99. // Name is char[10]
  100. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  101. send_named_float("CamTilt",
  102. 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));
  103. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  104. send_named_float("CamPan",
  105. 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));
  106. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  107. send_named_float("TetherTrn",
  108. sub.quarter_turn_count/4);
  109. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  110. send_named_float("Lights1",
  111. SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);
  112. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  113. send_named_float("Lights2",
  114. SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);
  115. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  116. send_named_float("PilotGain", sub.gain);
  117. CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
  118. send_named_float("InputHold", sub.input_hold_engaged);
  119. return true;
  120. }
  121. /*
  122. send PID tuning message
  123. */
  124. void GCS_MAVLINK_Sub::send_pid_tuning()
  125. {
  126. const Parameters &g = sub.g;
  127. AP_AHRS &ahrs = AP::ahrs();
  128. AC_AttitudeControl_Sub &attitude_control = sub.attitude_control;
  129. const Vector3f &gyro = ahrs.get_gyro();
  130. if (g.gcs_pid_mask & 1) {
  131. const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
  132. mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
  133. pid_info.target*0.01f,
  134. degrees(gyro.x),
  135. pid_info.FF*0.01f,
  136. pid_info.P*0.01f,
  137. pid_info.I*0.01f,
  138. pid_info.D*0.01f);
  139. if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
  140. return;
  141. }
  142. }
  143. if (g.gcs_pid_mask & 2) {
  144. const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info();
  145. mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
  146. pid_info.target*0.01f,
  147. degrees(gyro.y),
  148. pid_info.FF*0.01f,
  149. pid_info.P*0.01f,
  150. pid_info.I*0.01f,
  151. pid_info.D*0.01f);
  152. if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
  153. return;
  154. }
  155. }
  156. if (g.gcs_pid_mask & 4) {
  157. const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info();
  158. mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
  159. pid_info.target*0.01f,
  160. degrees(gyro.z),
  161. pid_info.FF*0.01f,
  162. pid_info.P*0.01f,
  163. pid_info.I*0.01f,
  164. pid_info.D*0.01f);
  165. if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
  166. return;
  167. }
  168. }
  169. if (g.gcs_pid_mask & 8) {
  170. const AP_Logger::PID_Info &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info();
  171. mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
  172. pid_info.target*0.01f,
  173. -(ahrs.get_accel_ef_blended().z + GRAVITY_MSS),
  174. pid_info.FF*0.01f,
  175. pid_info.P*0.01f,
  176. pid_info.I*0.01f,
  177. pid_info.D*0.01f);
  178. if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
  179. return;
  180. }
  181. }
  182. }
  183. uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const
  184. {
  185. return sub.g.sysid_my_gcs;
  186. }
  187. bool GCS_Sub::vehicle_initialised() const {
  188. return sub.ap.initialised;
  189. }
  190. // try to send a message, return false if it won't fit in the serial tx buffer
  191. bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
  192. {
  193. switch (id) {
  194. case MSG_NAMED_FLOAT:
  195. send_info();
  196. break;
  197. case MSG_TERRAIN:
  198. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  199. CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
  200. sub.terrain.send_request(chan);
  201. #endif
  202. break;
  203. default:
  204. return GCS_MAVLINK::try_send_message(id);
  205. }
  206. return true;
  207. }
  208. const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  209. // @Param: RAW_SENS
  210. // @DisplayName: Raw sensor stream rate
  211. // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station
  212. // @Units: Hz
  213. // @Range: 0 10
  214. // @Increment: 1
  215. // @User: Advanced
  216. AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 0),
  217. // @Param: EXT_STAT
  218. // @DisplayName: Extended status stream rate to ground station
  219. // @Description: Stream rate of SYS_STATUS, MEMINFO, MISSION_CURRENT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and LIMITS_STATUS to ground station
  220. // @Units: Hz
  221. // @Range: 0 10
  222. // @Increment: 1
  223. // @User: Advanced
  224. AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 0),
  225. // @Param: RC_CHAN
  226. // @DisplayName: RC Channel stream rate to ground station
  227. // @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS_RAW to ground station
  228. // @Units: Hz
  229. // @Range: 0 10
  230. // @Increment: 1
  231. // @User: Advanced
  232. AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 0),
  233. // @Param: POSITION
  234. // @DisplayName: Position stream rate to ground station
  235. // @Description: Stream rate of GLOBAL_POSITION_INT to ground station
  236. // @Units: Hz
  237. // @Range: 0 10
  238. // @Increment: 1
  239. // @User: Advanced
  240. AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 0),
  241. // @Param: EXTRA1
  242. // @DisplayName: Extra data type 1 stream rate to ground station
  243. // @Description: Stream rate of ATTITUDE and SIMSTATE (SITL only) to ground station
  244. // @Units: Hz
  245. // @Range: 0 10
  246. // @Increment: 1
  247. // @User: Advanced
  248. AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 0),
  249. // @Param: EXTRA2
  250. // @DisplayName: Extra data type 2 stream rate to ground station
  251. // @Description: Stream rate of VFR_HUD to ground station
  252. // @Units: Hz
  253. // @Range: 0 10
  254. // @Increment: 1
  255. // @User: Advanced
  256. AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 0),
  257. // @Param: EXTRA3
  258. // @DisplayName: Extra data type 3 stream rate to ground station
  259. // @Description: Stream rate of AHRS, HWSTATUS, and SYSTEM_TIME to ground station
  260. // @Units: Hz
  261. // @Range: 0 10
  262. // @Increment: 1
  263. // @User: Advanced
  264. AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 0),
  265. // @Param: PARAMS
  266. // @DisplayName: Parameter stream rate to ground station
  267. // @Description: Stream rate of PARAM_VALUE to ground station
  268. // @Units: Hz
  269. // @Range: 0 10
  270. // @Increment: 1
  271. // @User: Advanced
  272. AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0),
  273. AP_GROUPEND
  274. };
  275. static const ap_message STREAM_RAW_SENSORS_msgs[] = {
  276. MSG_RAW_IMU,
  277. MSG_SCALED_IMU2,
  278. MSG_SCALED_IMU3,
  279. MSG_SCALED_PRESSURE,
  280. MSG_SCALED_PRESSURE2,
  281. MSG_SCALED_PRESSURE3,
  282. MSG_SENSOR_OFFSETS
  283. };
  284. static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
  285. MSG_SYS_STATUS,
  286. MSG_POWER_STATUS,
  287. MSG_MEMINFO,
  288. MSG_CURRENT_WAYPOINT,
  289. MSG_GPS_RAW,
  290. MSG_GPS_RTK,
  291. MSG_GPS2_RAW,
  292. MSG_GPS2_RTK,
  293. MSG_NAV_CONTROLLER_OUTPUT,
  294. MSG_FENCE_STATUS,
  295. MSG_NAMED_FLOAT
  296. };
  297. static const ap_message STREAM_POSITION_msgs[] = {
  298. MSG_LOCATION,
  299. MSG_LOCAL_POSITION
  300. };
  301. static const ap_message STREAM_RC_CHANNELS_msgs[] = {
  302. MSG_SERVO_OUTPUT_RAW,
  303. MSG_RC_CHANNELS,
  304. MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
  305. };
  306. static const ap_message STREAM_EXTRA1_msgs[] = {
  307. MSG_ATTITUDE,
  308. MSG_SIMSTATE,
  309. MSG_AHRS2,
  310. MSG_AHRS3,
  311. MSG_PID_TUNING
  312. };
  313. static const ap_message STREAM_EXTRA2_msgs[] = {
  314. MSG_VFR_HUD
  315. };
  316. static const ap_message STREAM_EXTRA3_msgs[] = {
  317. MSG_AHRS,
  318. MSG_HWSTATUS,
  319. MSG_SYSTEM_TIME,
  320. MSG_RANGEFINDER,
  321. MSG_DISTANCE_SENSOR,
  322. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  323. MSG_TERRAIN,
  324. #endif
  325. MSG_BATTERY2,
  326. MSG_BATTERY_STATUS,
  327. MSG_MOUNT_STATUS,
  328. MSG_OPTICAL_FLOW,
  329. MSG_GIMBAL_REPORT,
  330. MSG_MAG_CAL_REPORT,
  331. MSG_MAG_CAL_PROGRESS,
  332. MSG_EKF_STATUS_REPORT,
  333. MSG_VIBRATION,
  334. #if RPM_ENABLED == ENABLED
  335. MSG_RPM,
  336. #endif
  337. MSG_ESC_TELEMETRY,
  338. };
  339. static const ap_message STREAM_PARAMS_msgs[] = {
  340. MSG_NEXT_PARAM
  341. };
  342. const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
  343. MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
  344. MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
  345. MAV_STREAM_ENTRY(STREAM_POSITION),
  346. MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
  347. MAV_STREAM_ENTRY(STREAM_EXTRA1),
  348. MAV_STREAM_ENTRY(STREAM_EXTRA2),
  349. MAV_STREAM_ENTRY(STREAM_EXTRA3),
  350. MAV_STREAM_ENTRY(STREAM_PARAMS),
  351. MAV_STREAM_TERMINATOR // must have this at end of stream_entries
  352. };
  353. bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
  354. {
  355. return sub.do_guided(cmd);
  356. }
  357. void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
  358. {
  359. // add home alt if needed
  360. if (cmd.content.location.relative_alt) {
  361. cmd.content.location.alt += sub.ahrs.get_home().alt;
  362. }
  363. // To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
  364. }
  365. MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro()
  366. {
  367. if (sub.motors.armed()) {
  368. gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
  369. return MAV_RESULT_FAILED;
  370. }
  371. if (!sub.control_check_barometer()) {
  372. return MAV_RESULT_FAILED;
  373. }
  374. AP::baro().calibrate(true);
  375. return MAV_RESULT_ACCEPTED;
  376. }
  377. MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
  378. {
  379. if (is_equal(packet.param6,1.0f)) {
  380. // compassmot calibration
  381. //result = sub.mavlink_compassmot(chan);
  382. gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
  383. return MAV_RESULT_UNSUPPORTED;
  384. }
  385. return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
  386. }
  387. MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)
  388. {
  389. if (!roi_loc.check_latlng()) {
  390. return MAV_RESULT_FAILED;
  391. }
  392. sub.set_auto_yaw_roi(roi_loc);
  393. return MAV_RESULT_ACCEPTED;
  394. }
  395. bool GCS_MAVLINK_Sub::set_home_to_current_location(bool lock) {
  396. return sub.set_home_to_current_location(lock);
  397. }
  398. bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool lock) {
  399. return sub.set_home(loc, lock);
  400. }
  401. MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet)
  402. {
  403. switch (packet.command) {
  404. case MAV_CMD_NAV_LOITER_UNLIM:
  405. if (!sub.set_mode(POSHOLD, MODE_REASON_GCS_COMMAND)) {
  406. return MAV_RESULT_FAILED;
  407. }
  408. return MAV_RESULT_ACCEPTED;
  409. case MAV_CMD_NAV_LAND:
  410. if (!sub.set_mode(SURFACE, MODE_REASON_GCS_COMMAND)) {
  411. return MAV_RESULT_FAILED;
  412. }
  413. return MAV_RESULT_ACCEPTED;
  414. case MAV_CMD_CONDITION_YAW:
  415. // param1 : target angle [0-360]
  416. // param2 : speed during change [deg per second]
  417. // param3 : direction (-1:ccw, +1:cw)
  418. // param4 : relative offset (1) or absolute angle (0)
  419. if ((packet.param1 >= 0.0f) &&
  420. (packet.param1 <= 360.0f) &&
  421. (is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
  422. sub.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
  423. return MAV_RESULT_ACCEPTED;
  424. }
  425. return MAV_RESULT_FAILED;
  426. case MAV_CMD_DO_CHANGE_SPEED:
  427. // param1 : unused
  428. // param2 : new speed in m/s
  429. // param3 : unused
  430. // param4 : unused
  431. if (packet.param2 > 0.0f) {
  432. sub.wp_nav.set_speed_xy(packet.param2 * 100.0f);
  433. return MAV_RESULT_ACCEPTED;
  434. }
  435. return MAV_RESULT_FAILED;
  436. case MAV_CMD_MISSION_START:
  437. if (sub.motors.armed() && sub.set_mode(AUTO, MODE_REASON_GCS_COMMAND)) {
  438. return MAV_RESULT_ACCEPTED;
  439. }
  440. return MAV_RESULT_FAILED;
  441. case MAV_CMD_DO_MOTOR_TEST:
  442. // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
  443. // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
  444. // param3 : throttle (range depends upon param2)
  445. // param4 : timeout (in seconds)
  446. if (!sub.handle_do_motor_test(packet)) {
  447. return MAV_RESULT_FAILED;
  448. }
  449. return MAV_RESULT_ACCEPTED;
  450. default:
  451. return GCS_MAVLINK::handle_command_long_packet(packet);
  452. }
  453. }
  454. mavlink_data64_t rov_message2;
  455. mavlink_motor_speed_t mav_motor_speed;
  456. mavlink_motor_speed_t mav_motor_speed_back;
  457. mavlink_rov_control_t rov_control{0,60,0};
  458. mavlink_rov_state_monitoring_t rov_message;
  459. //rov_message.hvMotorMod = 0xFFFF;
  460. mavlink_set_slave_parameter_t set_stm32_param{0xFF,0xFF,0,0,0,0,0};
  461. mavlink_set_slave_parameter_t get_stm32_param{0xFF,0xF1,0,0,0,0,0};
  462. mavlink_hv_reg_set_t hv_reg_set = {0xF0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
  463. mavlink_hv_reg_get_t hv_reg_get;
  464. void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
  465. {
  466. switch (msg.msgid) {
  467. case MAVLINK_MSG_ID_SET_SLAVE_PARAMETER:{//ok
  468. mavlink_set_slave_parameter_t packet;
  469. mavlink_msg_set_slave_parameter_decode(&msg,&packet);
  470. set_stm32_param = packet;
  471. //gcs().send_text(MAV_SEVERITY_WARNING, "MAVLINK_MSG_ID_SET_SLAVE_PARAMETER .");
  472. break;
  473. }
  474. case MAVLINK_MSG_ID_ROV_STATE_MONITORING:{
  475. mavlink_rov_state_monitoring_t packet;
  476. mavlink_msg_rov_state_monitoring_decode(&msg, &packet);
  477. rov_message = packet;
  478. //gcs().send_text(MAV_SEVERITY_INFO, "MAVLINK_MSG_ID_ROV_STATE_MONITORING .");
  479. break;
  480. }
  481. case MAVLINK_MSG_ID_MOTOR_SPEED:{//ok
  482. mavlink_motor_speed_t packet;
  483. mavlink_msg_motor_speed_decode(&msg, &packet);
  484. mav_motor_speed = packet;
  485. break;
  486. }
  487. case MAVLINK_MSG_ID_ROV_CONTROL:{//ok
  488. mavlink_rov_control_t packet;
  489. mavlink_msg_rov_control_decode(&msg, &packet);
  490. rov_control = packet;
  491. break;
  492. }
  493. case MAVLINK_MSG_ID_HV_REG_SET:{
  494. mavlink_hv_reg_set_t packet;
  495. mavlink_msg_hv_reg_set_decode(&msg, &packet);
  496. hv_reg_set = packet;
  497. //gcs().send_text(MAV_SEVERITY_WARNING, "MAVLINK_MSG_ID_HV_REG_SET .");
  498. break;
  499. }
  500. case MAVLINK_MSG_ID_HEARTBEAT: { // MAV ID: 0
  501. // We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
  502. if (msg.sysid != sub.g.sysid_my_gcs) {
  503. break;
  504. }
  505. sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
  506. break;
  507. }
  508. case MAVLINK_MSG_ID_MANUAL_CONTROL: { // MAV ID: 69
  509. if (msg.sysid != sub.g.sysid_my_gcs) {
  510. break; // Only accept control from our gcs
  511. }
  512. mavlink_manual_control_t packet;
  513. mavlink_msg_manual_control_decode(&msg, &packet);
  514. if (packet.target != sub.g.sysid_this_mav) {
  515. break; // only accept control aimed at us
  516. }
  517. sub.transform_manual_control_to_rc_override(packet.x,packet.y,packet.z,packet.r,packet.buttons);
  518. sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
  519. // a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
  520. sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
  521. break;
  522. }
  523. case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
  524. // decode packet
  525. mavlink_set_attitude_target_t packet;
  526. mavlink_msg_set_attitude_target_decode(&msg, &packet);
  527. // ensure type_mask specifies to use attitude
  528. // the thrust can be used from the altitude hold
  529. if (packet.type_mask & (1<<6)) {
  530. sub.set_attitude_target_no_gps = {AP_HAL::millis(), packet};
  531. }
  532. // ensure type_mask specifies to use attitude and thrust
  533. if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {
  534. break;
  535. }
  536. // convert thrust to climb rate
  537. packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);
  538. float climb_rate_cms = 0.0f;
  539. if (is_equal(packet.thrust, 0.5f)) {
  540. climb_rate_cms = 0.0f;
  541. } else if (packet.thrust > 0.5f) {
  542. // climb at up to WPNAV_SPEED_UP
  543. climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up();
  544. } else {
  545. // descend at up to WPNAV_SPEED_DN
  546. climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * fabsf(sub.wp_nav.get_default_speed_down());
  547. }
  548. sub.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);
  549. break;
  550. }
  551. case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84
  552. // decode packet
  553. mavlink_set_position_target_local_ned_t packet;
  554. mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
  555. // exit if vehicle is not in Guided mode or Auto-Guided mode
  556. if ((sub.control_mode != GUIDED) && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided)) {
  557. break;
  558. }
  559. // check for supported coordinate frames
  560. if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
  561. packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
  562. packet.coordinate_frame != MAV_FRAME_BODY_NED &&
  563. packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
  564. break;
  565. }
  566. bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
  567. bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
  568. bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
  569. /*
  570. * for future use:
  571. * bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
  572. * bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
  573. * bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
  574. */
  575. // prepare position
  576. Vector3f pos_vector;
  577. if (!pos_ignore) {
  578. // convert to cm
  579. pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);
  580. // rotate to body-frame if necessary
  581. if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||
  582. packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
  583. sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);
  584. }
  585. // add body offset if necessary
  586. if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
  587. packet.coordinate_frame == MAV_FRAME_BODY_NED ||
  588. packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
  589. pos_vector += sub.inertial_nav.get_position();
  590. } else {
  591. // convert from alt-above-home to alt-above-ekf-origin
  592. pos_vector.z = sub.pv_alt_above_origin(pos_vector.z);
  593. }
  594. }
  595. // prepare velocity
  596. Vector3f vel_vector;
  597. if (!vel_ignore) {
  598. // convert to cm
  599. vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f);
  600. // rotate to body-frame if necessary
  601. if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
  602. sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);
  603. }
  604. }
  605. // send request
  606. if (!pos_ignore && !vel_ignore && acc_ignore) {
  607. sub.guided_set_destination_posvel(pos_vector, vel_vector);
  608. } else if (pos_ignore && !vel_ignore && acc_ignore) {
  609. sub.guided_set_velocity(vel_vector);
  610. } else if (!pos_ignore && vel_ignore && acc_ignore) {
  611. sub.guided_set_destination(pos_vector);
  612. }
  613. break;
  614. }
  615. case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86
  616. // decode packet
  617. mavlink_set_position_target_global_int_t packet;
  618. mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
  619. // exit if vehicle is not in Guided, Auto-Guided, or Depth Hold modes
  620. if ((sub.control_mode != GUIDED)
  621. && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided)
  622. && !(sub.control_mode == ALT_HOLD)) {
  623. break;
  624. }
  625. bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
  626. bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
  627. bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
  628. /*
  629. * for future use:
  630. * bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
  631. * bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
  632. * bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
  633. */
  634. if (!pos_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD
  635. sub.pos_control.set_alt_target(packet.alt*100);
  636. break;
  637. }
  638. Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
  639. if (!pos_ignore) {
  640. // sanity check location
  641. if (!check_latlng(packet.lat_int, packet.lon_int)) {
  642. break;
  643. }
  644. Location::AltFrame frame;
  645. if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {
  646. // unknown coordinate frame
  647. break;
  648. }
  649. const Location loc{
  650. packet.lat_int,
  651. packet.lon_int,
  652. int32_t(packet.alt*100),
  653. frame,
  654. };
  655. if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {
  656. break;
  657. }
  658. }
  659. if (!pos_ignore && !vel_ignore && acc_ignore) {
  660. sub.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
  661. } else if (pos_ignore && !vel_ignore && acc_ignore) {
  662. sub.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
  663. } else if (!pos_ignore && vel_ignore && acc_ignore) {
  664. sub.guided_set_destination(pos_neu_cm);
  665. }
  666. break;
  667. }
  668. case MAVLINK_MSG_ID_DISTANCE_SENSOR: {
  669. sub.rangefinder.handle_msg(msg);
  670. break;
  671. }
  672. case MAVLINK_MSG_ID_TERRAIN_DATA:
  673. case MAVLINK_MSG_ID_TERRAIN_CHECK:
  674. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  675. sub.terrain.handle_data(chan, msg);
  676. #endif
  677. break;
  678. case MAVLINK_MSG_ID_SET_HOME_POSITION: {
  679. mavlink_set_home_position_t packet;
  680. mavlink_msg_set_home_position_decode(&msg, &packet);
  681. if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
  682. if (!sub.set_home_to_current_location(true)) {
  683. // ignore this failure
  684. }
  685. } else {
  686. Location new_home_loc;
  687. new_home_loc.lat = packet.latitude;
  688. new_home_loc.lng = packet.longitude;
  689. new_home_loc.alt = packet.altitude / 10;
  690. if (sub.far_from_EKF_origin(new_home_loc)) {
  691. break;
  692. }
  693. if (!sub.set_home(new_home_loc, true)) {
  694. // silently ignored
  695. }
  696. }
  697. break;
  698. }
  699. // This adds support for leak detectors in a separate enclosure
  700. // connected to a mavlink enabled subsystem
  701. case MAVLINK_MSG_ID_SYS_STATUS: {
  702. uint32_t MAV_SENSOR_WATER = 0x20000000;
  703. mavlink_sys_status_t packet;
  704. mavlink_msg_sys_status_decode(&msg, &packet);
  705. if ((packet.onboard_control_sensors_enabled & MAV_SENSOR_WATER) && !(packet.onboard_control_sensors_health & MAV_SENSOR_WATER)) {
  706. sub.leak_detector.set_detect();
  707. }
  708. }
  709. break;
  710. default:
  711. handle_common_message(msg);
  712. break;
  713. } // end switch
  714. } // end handle mavlink
  715. uint64_t GCS_MAVLINK_Sub::capabilities() const
  716. {
  717. return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
  718. MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
  719. MAV_PROTOCOL_CAPABILITY_MISSION_INT |
  720. MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
  721. MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
  722. MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
  723. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  724. (sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
  725. #endif
  726. MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
  727. GCS_MAVLINK::capabilities()
  728. );
  729. }
  730. // a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
  731. void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t &msg)
  732. {
  733. sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
  734. GCS_MAVLINK::handle_rc_channels_override(msg);
  735. }
  736. /*
  737. * a delay() callback that processes MAVLink packets. We set this as the
  738. * callback in long running library initialisation routines to allow
  739. * MAVLink to process packets while waiting for the initialisation to
  740. * complete
  741. */
  742. void Sub::mavlink_delay_cb()
  743. {
  744. static uint32_t last_1hz, last_50hz, last_5s;
  745. logger.EnableWrites(false);
  746. uint32_t tnow = AP_HAL::millis();
  747. if (tnow - last_1hz > 1000) {
  748. last_1hz = tnow;
  749. gcs().send_message(MSG_HEARTBEAT);
  750. gcs().send_message(MSG_SYS_STATUS);
  751. }
  752. if (tnow - last_50hz > 20) {
  753. last_50hz = tnow;
  754. gcs().update_receive();
  755. gcs().update_send();
  756. notify.update();
  757. }
  758. if (tnow - last_5s > 5000) {
  759. last_5s = tnow;
  760. gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
  761. }
  762. logger.EnableWrites(true);
  763. }
  764. MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
  765. if (packet.param1 > 0.5f) {
  766. sub.arming.disarm();
  767. return MAV_RESULT_ACCEPTED;
  768. }
  769. return MAV_RESULT_FAILED;
  770. }
  771. bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
  772. {
  773. return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
  774. }
  775. int32_t GCS_MAVLINK_Sub::global_position_int_alt() const {
  776. if (!sub.ap.depth_sensor_present) {
  777. return 0;
  778. }
  779. return GCS_MAVLINK::global_position_int_alt();
  780. }
  781. int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const {
  782. if (!sub.ap.depth_sensor_present) {
  783. return 0;
  784. }
  785. return GCS_MAVLINK::global_position_int_relative_alt();
  786. }
  787. // dummy method to avoid linking AFS
  788. bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }