kuka_interface.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. #define BOOST_TEST_DYN_LINK
  2. #include "core/basic_obj_types.hpp"
  3. #include "core/global_defs.h"
  4. #include "core/sophiar_pool.h"
  5. #include "utility/debug_utility.hpp"
  6. #include "utility/variable_helper.hpp"
  7. #include <boost/asio/co_spawn.hpp>
  8. #include <boost/asio/detached.hpp>
  9. #include <boost/test/unit_test.hpp>
  10. #include <spdlog/spdlog.h>
  11. #include <fstream>
  12. #include <numbers>
  13. using namespace sophiar;
  14. using namespace std::chrono_literals;
  15. using boost::asio::co_spawn;
  16. using boost::asio::awaitable;
  17. using boost::asio::detached;
  18. awaitable<void> test_kuka_joint_angle_control() {
  19. auto joint_angle_index = REQUIRE_VARIABLE(array7_obj, "kuka_joint_angle");
  20. auto joint_angle = VARIABLE_AUTO_DELEGATE(array7_obj, joint_angle_index);
  21. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  22. auto target_index = REQUIRE_VARIABLE(array7_obj, "target_joint_angle");
  23. co_await coro_wait_for_not_empty<array7_obj>(joint_angle_index);
  24. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  25. auto next_joint_angle = array7_obj::new_instance();
  26. next_joint_angle->value = joint_angle->value;
  27. next_joint_angle->value[6] += std::numbers::pi / 4;
  28. UPDATE_VARIABLE(array7_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. co_await joint_angle.coro_wait_update();
  34. next_joint_angle = array7_obj::new_instance();
  35. next_joint_angle->value = joint_angle->value;
  36. next_joint_angle->value[6] -= std::numbers::pi / 4;
  37. UPDATE_VARIABLE(array7_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_kuka_flange_pose_control() {
  45. auto flange_pose_index = REQUIRE_VARIABLE(transform_obj, "robot_flange_pose");
  46. auto flange_pose = VARIABLE_AUTO_DELEGATE(transform_obj, flange_pose_index);
  47. auto var_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  48. auto target_index = REQUIRE_VARIABLE(transform_obj, "target_flange_pose");
  49. co_await coro_wait_for_not_empty<transform_obj>(flange_pose_index);
  50. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  51. auto next_flange_pose = transform_obj::new_instance();
  52. next_flange_pose->value = flange_pose->value;
  53. next_flange_pose->value.translation().z() += 30;
  54. UPDATE_VARIABLE(transform_obj, target_index, next_flange_pose);
  55. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  56. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  57. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  58. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  59. co_await flange_pose.coro_wait_update();
  60. next_flange_pose = transform_obj::new_instance();
  61. next_flange_pose->value = flange_pose->value;
  62. next_flange_pose->value.translation().z() -= 30;
  63. UPDATE_VARIABLE(transform_obj, target_index, next_flange_pose);
  64. co_await coro_wait_for_variable_value<bool_obj>(var_index, true);
  65. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == true);
  66. co_await coro_wait_for_variable_value<bool_obj>(var_index, false);
  67. BOOST_TEST(QUERY_VARIABLE(bool_obj, var_index)->value == false);
  68. co_return;
  69. }
  70. BOOST_AUTO_TEST_CASE(test_kuka_interface) {
  71. spdlog::set_level(spdlog::level::trace);
  72. std::ifstream config_file("data/kuka_interface_config.json");
  73. BOOST_TEST(config_file.is_open());
  74. auto config = nlohmann::json::parse(config_file);
  75. BOOST_TEST(initialize(config));
  76. co_spawn(*global_context, test_kuka_flange_pose_control(), detached);
  77. global_context->run();
  78. }