ur_interface.cpp 6.2 KB

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