test_node.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120
  1. /*
  2. * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
  3. */
  4. #include <iostream>
  5. #include <uavcan_linux/uavcan_linux.hpp>
  6. #include <uavcan/protocol/node_status_monitor.hpp>
  7. #include "debug.hpp"
  8. static uavcan_linux::NodePtr initNode(const std::vector<std::string>& ifaces, uavcan::NodeID nid,
  9. const std::string& name)
  10. {
  11. auto node = uavcan_linux::makeNode(ifaces);
  12. /*
  13. * Configuring the node.
  14. */
  15. node->setNodeID(nid);
  16. node->setName(name.c_str());
  17. node->getLogger().setLevel(uavcan::protocol::debug::LogLevel::DEBUG);
  18. /*
  19. * Starting the node.
  20. */
  21. std::cout << "Starting the node..." << std::endl;
  22. const int start_res = node->start();
  23. std::cout << "Start returned: " << start_res << std::endl;
  24. ENFORCE(0 == start_res);
  25. std::cout << "Node started successfully" << std::endl;
  26. /*
  27. * Say Hi to the world.
  28. */
  29. node->setModeOperational();
  30. node->logInfo("init", "Hello world! I'm [%*], NID %*",
  31. node->getNodeStatusProvider().getName().c_str(), int(node->getNodeID().get()));
  32. return node;
  33. }
  34. static void runForever(const uavcan_linux::NodePtr& node)
  35. {
  36. /*
  37. * Subscribing to the UAVCAN logging topic
  38. */
  39. auto log_handler = [](const uavcan::ReceivedDataStructure<uavcan::protocol::debug::LogMessage>& msg)
  40. {
  41. std::cout << msg << std::endl;
  42. };
  43. auto log_sub = node->makeSubscriber<uavcan::protocol::debug::LogMessage>(log_handler);
  44. /*
  45. * Printing when other nodes enter the network or change status
  46. */
  47. struct NodeStatusMonitor : public uavcan::NodeStatusMonitor
  48. {
  49. explicit NodeStatusMonitor(uavcan::INode& node) : uavcan::NodeStatusMonitor(node) { }
  50. void handleNodeStatusChange(const NodeStatusChangeEvent& event) override
  51. {
  52. std::cout << "Remote node NID " << int(event.node_id.get()) << " changed status: "
  53. << event.old_status.toString() << " --> "
  54. << event.status.toString() << std::endl;
  55. }
  56. };
  57. NodeStatusMonitor nsm(*node);
  58. ENFORCE(0 == nsm.start());
  59. /*
  60. * Adding a stupid timer that does nothing once a minute
  61. */
  62. auto do_nothing_once_a_minute = [&node](const uavcan::TimerEvent&)
  63. {
  64. node->logInfo("timer", "Another minute passed...");
  65. // coverity[dont_call]
  66. node->setVendorSpecificStatusCode(static_cast<std::uint16_t>(std::rand())); // Setting to an arbitrary value
  67. };
  68. auto timer = node->makeTimer(uavcan::MonotonicDuration::fromMSec(60000), do_nothing_once_a_minute);
  69. /*
  70. * Spinning forever
  71. */
  72. while (true)
  73. {
  74. const int res = node->spin(uavcan::MonotonicDuration::getInfinite());
  75. if (res < 0)
  76. {
  77. node->logError("spin", "Error %*", res);
  78. }
  79. }
  80. }
  81. int main(int argc, const char** argv)
  82. {
  83. try
  84. {
  85. if (argc < 3)
  86. {
  87. std::cerr << "Usage:\n\t" << argv[0] << " <node-id> <can-iface-name-1> [can-iface-name-N...]" << std::endl;
  88. return 1;
  89. }
  90. const int self_node_id = std::stoi(argv[1]);
  91. std::vector<std::string> iface_names;
  92. for (int i = 2; i < argc; i++)
  93. {
  94. iface_names.emplace_back(argv[i]);
  95. }
  96. uavcan_linux::NodePtr node = initNode(iface_names, self_node_id, "org.uavcan.linux_test_node");
  97. std::cout << "Node initialized successfully" << std::endl;
  98. runForever(node);
  99. return 0;
  100. }
  101. catch (const std::exception& ex)
  102. {
  103. std::cerr << "Exception: " << ex.what() << std::endl;
  104. return 1;
  105. }
  106. }