five_dof_offset_calculator.hpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354
  1. #ifndef SOPHIAR2_FIVE_DOF_OFFSET_CALCULATOR_HPP
  2. #define SOPHIAR2_FIVE_DOF_OFFSET_CALCULATOR_HPP
  3. #include "core/basic_obj_types.hpp"
  4. #include "utility/config_utility.hpp"
  5. #include "utility/coro_signal_group.hpp"
  6. #include "utility/coro_worker.hpp"
  7. #include "utility/simple_tristate_obj.hpp"
  8. #include "utility/variable_helper.hpp"
  9. namespace sophiar {
  10. // Fix origin and Z-axis only
  11. inline coro_worker::pointer make_5dof_offset_calculator_func(const nlohmann::json &config) {
  12. auto cur_index = LOAD_VARIABLE_INDEX(transform_obj, "current_transform_var");
  13. auto tar_index = LOAD_VARIABLE_INDEX(transform_obj, "target_transform_var");
  14. auto offset_index = LOAD_VARIABLE_INDEX(transform_obj, "offset_transform_var");
  15. auto signal_group = coro_signal_any_group::new_instance();
  16. signal_group->add_watcher(REQUIRE_VARIABLE_WATCHER(cur_index));
  17. signal_group->add_watcher(REQUIRE_VARIABLE_WATCHER(tar_index));
  18. auto signal_watcher = signal_group->new_watcher();
  19. signal_group->start();
  20. auto exit_func = SIGNAL_GROUP_AUTO_CLOSER(signal_group);
  21. auto worker = make_infinite_coro_worker(
  22. [=,
  23. watcher = std::move(signal_watcher)]() mutable
  24. -> boost::asio::awaitable<bool> {
  25. co_await watcher.coro_wait(false);
  26. auto ts = watcher.get_last_update_ts();
  27. auto cur_trans = QUERY_VARIABLE(transform_obj, cur_index);
  28. auto tar_trans = QUERY_VARIABLE(transform_obj, tar_index);
  29. if (cur_trans == nullptr || tar_trans == nullptr) [[unlikely]] {
  30. UPDATE_VARIABLE_WITH_TS(transform_obj, offset_index, nullptr, ts);
  31. } else [[likely]] {
  32. auto dof6_trans = cur_trans->value.inverse() * tar_trans->value;
  33. auto z_axis = Eigen::Vector3d::UnitZ();
  34. auto new_z_axis = dof6_trans.linear() * z_axis;
  35. auto dof5_rot = Eigen::Quaterniond::FromTwoVectors(z_axis, new_z_axis);
  36. auto dof5_trans = Eigen::Translation3d{dof6_trans.translation()};
  37. auto offset = transform_obj::new_instance();
  38. offset->value = dof5_trans * dof5_rot;
  39. UPDATE_VARIABLE_WITH_TS(transform_obj, offset_index, offset, ts);
  40. }
  41. co_return true;
  42. }, std::move(exit_func));
  43. return std::move(worker);
  44. }
  45. }
  46. #endif //SOPHIAR2_FIVE_DOF_OFFSET_CALCULATOR_HPP