4 #include "behaviortree_cpp/flatbuffers/BT_logger_generated.h"
16 return Serialization::NodeType::ACTION;
18 return Serialization::NodeType::DECORATOR;
20 return Serialization::NodeType::CONTROL;
22 return Serialization::NodeType::CONDITION;
24 return Serialization::NodeType::SUBTREE;
37 return Serialization::NodeStatus::IDLE;
39 return Serialization::NodeStatus::SUCCESS;
41 return Serialization::NodeStatus::RUNNING;
43 return Serialization::NodeStatus::FAILURE;
45 return Serialization::NodeStatus::IDLE;
53 return Serialization::PortDirection::INPUT;
55 return Serialization::PortDirection::OUTPUT;
57 return Serialization::PortDirection::INOUT;
59 return Serialization::PortDirection::INOUT;
65 std::vector<flatbuffers::Offset<Serialization::TreeNode>> fb_nodes;
68 std::vector<uint16_t> children_uid;
69 if(auto control = dynamic_cast<BT::ControlNode*>(node))
71 children_uid.reserve(control->children().size());
72 for(const auto& child : control->children())
74 children_uid.push_back(child->UID());
79 const auto& child = decorator->child();
80 children_uid.push_back(child->UID());
85 std::vector<flatbuffers::Offset<Serialization::PortConfig>> ports;
86 for(
const auto& it : node_config.input_ports)
88 ports.push_back(Serialization::CreatePortConfigDirect(builder, it.first.c_str(),
91 for(
const auto& it : node_config.output_ports)
93 ports.push_back(Serialization::CreatePortConfigDirect(builder, it.first.c_str(),
97 auto tn = Serialization::CreateTreeNode(
98 builder, node->
UID(), builder.CreateVector(children_uid),
101 builder.CreateVector(ports));
103 fb_nodes.push_back(tn);
106 std::vector<flatbuffers::Offset<Serialization::NodeModel>> node_models;
108 for(
const auto& node_it : tree.manifests)
110 const auto&
manifest = node_it.second;
111 std::vector<flatbuffers::Offset<Serialization::PortModel>> port_models;
113 for(
const auto& port_it :
manifest.ports)
115 const auto& port_name = port_it.first;
116 const auto& port = port_it.second;
117 auto port_model = Serialization::CreatePortModel(
118 builder, builder.CreateString(port_name.c_str()),
120 builder.CreateString(
demangle(port.type()).c_str()),
121 builder.CreateString(port.description().c_str()));
122 port_models.push_back(port_model);
125 auto node_model = Serialization::CreateNodeModel(
126 builder, builder.CreateString(
manifest.registration_ID.c_str()),
129 node_models.push_back(node_model);
132 auto behavior_tree = Serialization::CreateBehaviorTree(
133 builder, tree.rootNode()->UID(), builder.CreateVector(fb_nodes),
134 builder.CreateVector(node_models));
136 builder.Finish(behavior_tree);
145 using namespace std::chrono;
147 int64_t usec = duration_cast<microseconds>(timestamp).count();
148 int64_t t_sec = usec / 1000000;
149 int64_t t_usec = usec % 1000000;
151 flatbuffers::WriteScalar(&
buffer[0], t_sec);
152 flatbuffers::WriteScalar(&
buffer[4], t_usec);
153 flatbuffers::WriteScalar(&
buffer[8], UID);
155 flatbuffers::WriteScalar(&
buffer[10],
157 flatbuffers::WriteScalar(&
buffer[11],