ur_interface.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. #define BOOST_TEST_DYN_LINK
  2. #define BOOST_TEST_MAIN // in only one cpp file
  3. #include "core/basic_obj_types.hpp"
  4. #include "core/global_defs.h"
  5. #include "core/sophiar_pool.h"
  6. #include "robot/ur/ur_interface.h"
  7. #include "utility/debug_utility.hpp"
  8. #include "utility/variable_helper.hpp"
  9. #include <boost/asio/co_spawn.hpp>
  10. #include <boost/asio/detached.hpp>
  11. #include <boost/test/unit_test.hpp>
  12. #include <spdlog/spdlog.h>
  13. #include <fstream>
  14. #include <numbers>
  15. using namespace sophiar;
  16. using namespace std::chrono_literals;
  17. using boost::asio::co_spawn;
  18. using boost::asio::awaitable;
  19. using boost::asio::detached;
  20. awaitable<void> test_joint_angle_control() {
  21. auto joint_angle = VARIABLE_AUTO_DELEGATE(array6_obj, "ur_joint_actual_q");
  22. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  23. auto target_index = REQUIRE_VARIABLE(array6_obj, "ur_target_joint_q");
  24. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  25. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  26. auto next_joint_angle = array6_obj::new_instance();
  27. next_joint_angle->value = joint_angle->value;
  28. next_joint_angle->value[0] += std::numbers::pi;
  29. UPDATE_VARIABLE(array6_obj, target_index, next_joint_angle);
  30. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  31. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  32. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  33. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  34. next_joint_angle = array6_obj::new_instance();
  35. next_joint_angle->value = joint_angle->value;
  36. next_joint_angle->value[0] -= std::numbers::pi;
  37. UPDATE_VARIABLE(array6_obj, target_index, next_joint_angle);
  38. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  39. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  40. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  41. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  42. co_return;
  43. }
  44. awaitable<void> test_joint_speed_control() {
  45. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  46. auto target_index = REQUIRE_VARIABLE(array6_obj, "ur_target_joint_qd");
  47. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  48. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  49. for (int i = 0; i < 40; ++i) {
  50. auto next_joint_speed = array6_obj::new_instance();
  51. next_joint_speed->value.fill({});
  52. next_joint_speed->value[0] = 0.2;
  53. UPDATE_VARIABLE(array6_obj, target_index, next_joint_speed);
  54. co_await coro_sleep(50ms);
  55. }
  56. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  57. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  58. for (int i = 0; i < 40; ++i) {
  59. auto next_joint_speed = array6_obj::new_instance();
  60. next_joint_speed->value.fill({});
  61. next_joint_speed->value[0] = -0.2;
  62. UPDATE_VARIABLE(array6_obj, target_index, next_joint_speed);
  63. co_await coro_sleep(50ms);
  64. }
  65. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  66. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  67. co_return;
  68. }
  69. awaitable<void> test_tcp_pose_control() {
  70. auto tcp_pose = VARIABLE_AUTO_DELEGATE(transform_obj, "robot_tcp_actual_pose");
  71. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  72. auto target_index = REQUIRE_VARIABLE(transform_obj, "robot_target_tcp_pose");
  73. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  74. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  75. auto next_tcp_pose = transform_obj::new_instance();
  76. next_tcp_pose->value = tcp_pose->value;
  77. next_tcp_pose->value.translation().z() += 0.1;
  78. UPDATE_VARIABLE(transform_obj, target_index, next_tcp_pose);
  79. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  80. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  81. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  82. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  83. next_tcp_pose = transform_obj::new_instance();
  84. next_tcp_pose->value = tcp_pose->value;
  85. next_tcp_pose->value.translation().z() -= 0.1;
  86. UPDATE_VARIABLE(transform_obj, target_index, next_tcp_pose);
  87. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  88. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  89. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  90. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  91. co_return;
  92. }
  93. awaitable<void> test_tcp_speed_control() {
  94. // set custom tcp
  95. auto tcp_offset_index = REQUIRE_VARIABLE(transform_obj, "robot_tcp_offset_pose");
  96. UPDATE_VARIABLE_VAL(transform_obj, tcp_offset_index, Eigen::Translation3d(0, 0, 0.15));
  97. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  98. auto target_index = REQUIRE_VARIABLE(array6_obj, "robot_target_tcp_speed");
  99. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  100. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  101. for (int i = 0; i < 40; ++i) {
  102. auto next_tcp_speed = array6_obj::new_instance();
  103. next_tcp_speed->value.fill({});
  104. next_tcp_speed->value[3] = 0.2;
  105. UPDATE_VARIABLE(array6_obj, target_index, next_tcp_speed);
  106. co_await coro_sleep(50ms);
  107. }
  108. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  109. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  110. for (int i = 0; i < 40; ++i) {
  111. auto next_tcp_speed = array6_obj::new_instance();
  112. next_tcp_speed->value.fill({});
  113. next_tcp_speed->value[3] = -0.2;
  114. UPDATE_VARIABLE(array6_obj, target_index, next_tcp_speed);
  115. co_await coro_sleep(50ms);
  116. }
  117. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  118. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  119. co_return;
  120. }
  121. BOOST_AUTO_TEST_CASE(test_ur_interface) {
  122. spdlog::set_level(spdlog::level::trace);
  123. std::ifstream config_file("data/ur_interface_config.json");
  124. BOOST_TEST(config_file.is_open());
  125. auto config = nlohmann::json::parse(config_file);
  126. BOOST_TEST(initialize(config));
  127. co_spawn(*global_context, test_tcp_pose_control(), detached);
  128. global_context->run();
  129. }