kuka_calibration.cpp 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586
  1. #include "core/basic_obj_types.hpp"
  2. #include "core/global_defs.h"
  3. #include "core/sophiar_pool.h"
  4. #include "utility/debug_utility.hpp"
  5. #include "utility/variable_helper.hpp"
  6. #include "utility/versatile_buffer2.hpp"
  7. #include <boost/asio/co_spawn.hpp>
  8. #include <boost/asio/detached.hpp>
  9. #include <spdlog/spdlog.h>
  10. #include <fstream>
  11. #include <iostream>
  12. #include <numbers>
  13. #include "utility/assert_utility.h"
  14. using namespace Eigen;
  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> collect_data() {
  21. static constexpr auto resolution = 32;
  22. static constexpr auto move_angle = 0.3;
  23. static constexpr auto move_distance = 75;
  24. static constexpr auto pi = std::numbers::pi;
  25. static constexpr auto step_angle = 2 * pi / resolution;
  26. auto flange_index = REQUIRE_VARIABLE(transform_obj, "flange_in_base");
  27. auto ref_index = REQUIRE_VARIABLE(transform_obj, "ref_in_tracker");
  28. auto is_moving_index = REQUIRE_VARIABLE(bool_obj, "robot_is_moving");
  29. auto target_index = REQUIRE_VARIABLE(transform_obj, "target_flange_pose");
  30. auto print_data = [=, ss = string_writer{}]() mutable {
  31. QUERY_VARIABLE(transform_obj, flange_index)->write_to(ss);
  32. std::cout << ss.get_string_and_reset() << std::endl;
  33. QUERY_VARIABLE(transform_obj, ref_index)->write_to(ss);
  34. std::cout << ss.get_string_and_reset() << std::endl;
  35. };
  36. // wait for robot ready
  37. co_await coro_wait_for_not_empty<transform_obj>(flange_index);
  38. co_await coro_wait_for_not_empty<transform_obj>(ref_index);
  39. // print initial states
  40. print_data();
  41. // start moving
  42. auto start_pose = QUERY_VARIABLE(transform_obj, flange_index);
  43. for (int i = 0; i < resolution; ++i) {
  44. auto angle = i * step_angle;
  45. auto rot_axis = Vector3d{cos(angle), sin(angle), 0};
  46. auto next_pose = transform_obj::new_instance();
  47. next_pose->value = start_pose->value
  48. * Translation3d{move_distance * rot_axis}
  49. * AngleAxisd{move_angle, rot_axis};
  50. UPDATE_VARIABLE(transform_obj, target_index, next_pose);
  51. // wait for movement to start and then finish
  52. co_await coro_wait_for_variable_value<bool_obj>(is_moving_index, true);
  53. co_await coro_wait_for_variable_value<bool_obj>(is_moving_index, false);
  54. // wait for robot to be stable
  55. co_await coro_sleep(1s);
  56. print_data();
  57. }
  58. // move back to start pose
  59. UPDATE_VARIABLE(transform_obj, target_index, start_pose);
  60. co_return;
  61. }
  62. int main() {
  63. spdlog::set_level(spdlog::level::trace);
  64. std::ifstream config_file("data/kuka_calibration_config.json");
  65. assert(config_file.is_open());
  66. auto config = nlohmann::json::parse(config_file);
  67. auto ok = initialize(config);
  68. assert(ok);
  69. co_spawn(*global_context, collect_data(), detached);
  70. global_context->run();
  71. }