You can not select more than 25 topics Topics must start with a chinese character,a letter or number, can include dashes ('-') and can be up to 35 characters long.

main.cc 3.6 kB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  1. #include "../build/dora-node-api.h"
  2. #include "../build/dora-ros2-bindings.h"
  3. #include <iostream>
  4. #include <vector>
  5. #include <random>
  6. int main()
  7. {
  8. std::cout << "HELLO FROM C++" << std::endl;
  9. auto dora_node = init_dora_node();
  10. auto merged_events = dora_events_into_combined(std::move(dora_node.events));
  11. auto qos = qos_default();
  12. qos.durability = Ros2Durability::Volatile;
  13. qos.liveliness = Ros2Liveliness::Automatic;
  14. qos.reliable = true;
  15. qos.max_blocking_time = 0.1;
  16. auto ros2_context = init_ros2_context();
  17. auto node = ros2_context->new_node("/ros2_demo", "turtle_teleop");
  18. auto vel_topic = node->create_topic_geometry_msgs_Twist("/turtle1", "cmd_vel", qos);
  19. auto vel_publisher = node->create_publisher(vel_topic, qos);
  20. auto pose_topic = node->create_topic_turtlesim_Pose("/turtle1", "pose", qos);
  21. auto pose_subscription = node->create_subscription(pose_topic, qos, merged_events);
  22. std::random_device dev;
  23. std::default_random_engine gen(dev());
  24. std::uniform_real_distribution<> dist(0., 1.);
  25. auto service_qos = qos_default();
  26. service_qos.reliable = true;
  27. service_qos.max_blocking_time = 0.1;
  28. service_qos.keep_last = 1;
  29. auto add_two_ints = node->create_client_example_interfaces_AddTwoInts("/", "add_two_ints", service_qos, merged_events);
  30. add_two_ints->wait_for_service(node);
  31. auto received_ticks = 0;
  32. auto responses_received = 0;
  33. for (int i = 0; i < 1000; i++)
  34. {
  35. auto event = merged_events.next();
  36. if (event.is_dora())
  37. {
  38. auto dora_event = downcast_dora(std::move(event));
  39. auto ty = event_type(dora_event);
  40. if (ty == DoraEventType::AllInputsClosed)
  41. {
  42. break;
  43. }
  44. else if (ty == DoraEventType::Input)
  45. {
  46. auto input = event_as_input(std::move(dora_event));
  47. received_ticks += 1;
  48. std::cout << "Received input " << std::string(input.id) << std::endl;
  49. geometry_msgs::Twist twist = {
  50. .linear = {.x = dist(gen) + 1, .y = 0, .z = 0},
  51. .angular = {.x = 0, .y = 0, .z = (dist(gen) - 0.5) * 5.0}};
  52. vel_publisher->publish(twist);
  53. example_interfaces::AddTwoInts_Request request = {.a = 4, .b = 5};
  54. add_two_ints->send_request(request);
  55. }
  56. else
  57. {
  58. std::cerr << "Unknown event type " << static_cast<int>(ty) << std::endl;
  59. }
  60. if (received_ticks > 20)
  61. {
  62. break;
  63. }
  64. }
  65. else if (pose_subscription->matches(event))
  66. {
  67. auto pose = pose_subscription->downcast(std::move(event));
  68. std::cout << "Received pose x:" << pose.x << ", y:" << pose.y << std::endl;
  69. }
  70. else if (add_two_ints->matches(event))
  71. {
  72. auto response = add_two_ints->downcast(std::move(event));
  73. assert(response.sum == 9);
  74. std::cout << "Received correct sum response from add_two_ints" << std::endl;
  75. responses_received += 1;
  76. }
  77. else
  78. {
  79. std::cout << "received unexpected event" << std::endl;
  80. }
  81. }
  82. std::cout << "Received " << responses_received << " service responses" << std::endl;
  83. assert(responses_received > 0);
  84. // try to access a constant for testing
  85. assert((sensor_msgs::const_NavSatStatus_STATUS_NO_FIX() == -1));
  86. std::cout << "GOODBYE FROM C++ node (using Rust API)" << std::endl;
  87. return 0;
  88. }