routing.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101
  1. //
  2. // Simple test for the GCS_MAVLink routing
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <GCS_MAVLink/GCS.h>
  6. #include <GCS_MAVLink/GCS_MAVLink.h>
  7. #include <GCS_MAVLink/GCS_Dummy.h>
  8. #include <AP_Common/AP_FWVersion.h>
  9. #include <AP_SerialManager/AP_SerialManager.h>
  10. void setup();
  11. void loop();
  12. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  13. AP_SerialManager _serialmanager;
  14. GCS_Dummy _gcs;
  15. extern mavlink_system_t mavlink_system;
  16. const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  17. AP_GROUPEND
  18. };
  19. static MAVLink_routing routing;
  20. void setup(void)
  21. {
  22. hal.console->printf("routing test startup...");
  23. gcs().setup_console();
  24. }
  25. void loop(void)
  26. {
  27. uint16_t err_count = 0;
  28. // incoming heartbeat
  29. mavlink_message_t msg;
  30. mavlink_heartbeat_t heartbeat = {0};
  31. mavlink_msg_heartbeat_encode(3, 1, &msg, &heartbeat);
  32. if (!routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  33. hal.console->printf("heartbeat should be processed locally\n");
  34. err_count++;
  35. }
  36. // incoming non-targetted message
  37. mavlink_attitude_t attitude = {0};
  38. mavlink_msg_attitude_encode(3, 1, &msg, &attitude);
  39. if (!routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  40. hal.console->printf("attitude should be processed locally\n");
  41. err_count++;
  42. }
  43. // incoming targeted message for someone else
  44. mavlink_param_set_t param_set = {0};
  45. param_set.target_system = mavlink_system.sysid+1;
  46. param_set.target_component = mavlink_system.compid;
  47. mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
  48. if (routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  49. hal.console->printf("param set 1 should not be processed locally\n");
  50. err_count++;
  51. }
  52. // incoming targeted message for us
  53. param_set.target_system = mavlink_system.sysid;
  54. param_set.target_component = mavlink_system.compid;
  55. mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
  56. if (!routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  57. hal.console->printf("param set 2 should be processed locally\n");
  58. err_count++;
  59. }
  60. // incoming targeted message for our system, but other compid
  61. // should be processed locally
  62. param_set.target_system = mavlink_system.sysid;
  63. param_set.target_component = mavlink_system.compid+1;
  64. mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
  65. if (!routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  66. hal.console->printf("param set 3 should be processed locally\n");
  67. err_count++;
  68. }
  69. // incoming broadcast message should be processed locally
  70. param_set.target_system = 0;
  71. param_set.target_component = mavlink_system.compid+1;
  72. mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
  73. if (!routing.check_and_forward(MAVLINK_COMM_0, msg)) {
  74. hal.console->printf("param set 4 should be processed locally\n");
  75. err_count++;
  76. }
  77. if (err_count == 0) {
  78. hal.console->printf("All OK\n");
  79. }
  80. hal.scheduler->delay(1000);
  81. }
  82. AP_HAL_MAIN();