| 123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111 |
- #ifndef SOPHIAR2_TRANSFORM_UTILITY_HPP
- #define SOPHIAR2_TRANSFORM_UTILITY_HPP
- #include "core/basic_obj_types.hpp"
- #include "utility/coro_signal_group.hpp"
- #include "utility/coro_worker.hpp"
- #include "utility/simple_tristate_obj.hpp"
- #include "utility/global_obj_helper.hpp"
- #include <cassert>
- namespace sophiar {
- inline coro_worker::pointer make_transform_inverter_func(const nlohmann::json &config) {
- assert(config.contains("input_obj_name"));
- assert(config.contains("output_obj_name"));
- assert(config["input_obj_name"].is_string());
- assert(config["output_obj_name"].is_string());
- auto input_obj_name = config["input_obj_name"].get<std::string>();
- auto output_obj_name = config["output_obj_name"].get<std::string>();
- auto input_obj_index = REGISTER_GLOBAL_OBJ(transform_obj, input_obj_name);
- auto output_obj_index = REGISTER_GLOBAL_OBJ(transform_obj, output_obj_name);
- auto worker = make_infinite_coro_worker(global_context, [=,
- input_helper = GLOBAL_OBJ_AUTO_DELEGATE(transform_obj, input_obj_index)]() mutable
- -> boost::asio::awaitable<bool> {
- co_await input_helper.coro_wait_update(false);
- auto ts = GLOBAL_OBJ_UPDATE_TS(input_obj_index);
- if (input_helper.empty()) [[unlikely]] {
- UPDATE_GLOBAL_OBJ_TS(transform_obj, output_obj_index, nullptr, ts);
- } else [[likely]] {
- auto new_trans = transform_obj::new_instance();
- new_trans->value = input_helper->value.inverse();
- UPDATE_GLOBAL_OBJ_TS(transform_obj, output_obj_index, new_trans, ts);
- }
- co_return true;
- });
- return std::move(worker);
- }
- scalarxyz_obj::value_type get_scalarxyz_from_json_list(const nlohmann::json &config) {
- assert(config.is_array());
- assert(config.size() == 3);
- double val[3];
- for (int i = 0; i < 3; ++i) {
- assert(config[i].is_number());
- val[i] = config[i].get<double>();
- }
- return {val[0], val[1], val[2]};
- }
- template<bool IsVector>
- inline coro_worker::pointer make_fixed_scalarxyz_transformer(const nlohmann::json &config) {
- assert(config["transform_type"] == "point");
- auto fixed_value = get_scalarxyz_from_json_list(config["fixed_value"]);
- auto trans_obj_name = config["transform_obj_name"].get<std::string>();
- auto output_obj_name = config["output_obj_name"].get<std::string>();
- auto trans_obj_index = REGISTER_GLOBAL_OBJ(transform_obj, trans_obj_name);
- auto output_obj_index = REGISTER_GLOBAL_OBJ(scalarxyz_obj, output_obj_name);
- auto worker = make_infinite_coro_worker(global_context, [=,
- trans_helper = GLOBAL_OBJ_AUTO_DELEGATE(transform_obj, trans_obj_index)]() mutable
- -> boost::asio::awaitable<bool> {
- co_await trans_helper.coro_wait_update(false);
- auto ts = GLOBAL_OBJ_UPDATE_TS(trans_obj_index);
- if (trans_helper.empty()) [[unlikely]] {
- UPDATE_GLOBAL_OBJ_TS(scalarxyz_obj, output_obj_index, nullptr, ts);
- } else [[likely]] {
- auto new_value = scalarxyz_obj::new_instance();
- if constexpr (IsVector) {
- new_value->value = trans_helper->value.linear() * fixed_value;
- } else {
- new_value->value = trans_helper->value * fixed_value;
- }
- UPDATE_GLOBAL_OBJ_TS(scalarxyz_obj, output_obj_index, new_value, ts);
- }
- co_return true;
- });
- return std::move(worker);
- }
- inline coro_worker::pointer make_scalarxyz_transformer(const nlohmann::json &config) {
- assert(config.contains("transform_obj_name"));
- assert(config.contains("output_obj_name"));
- assert(config["transform_obj_name"].is_string());
- assert(config["output_obj_name"].is_string());
- assert(config.contains("transform_type"));
- assert(config["transform_type"].is_string());
- auto trans_type = config["transform_type"].get<std::string>();
- if (config.contains("fixed_value")) {
- if (trans_type == "vector") {
- return make_fixed_scalarxyz_transformer<true>(config);
- } else {
- assert(trans_type == "point");
- return make_fixed_scalarxyz_transformer<false>(config);
- }
- } else {
- assert(config.contains("input_obj_name"));
- assert(config["input_obj_name"].is_string());
- // TODO 实现 dynamic_scalaxyz_transformer
- assert(false);
- return nullptr;
- }
- assert(false);
- return nullptr;
- }
- using transform_inverter = simple_tristate_obj_wrapper<make_transform_inverter_func>;
- using scalarxyz_transformer = simple_tristate_obj_wrapper<make_scalarxyz_transformer>;
- }
- #endif //SOPHIAR2_TRANSFORM_UTILITY_HPP
|