Basic Constructs
- BT ports: BehaviorTree-CPP needs a compile-time contract for every node type, a list of ports (name + type + optional default + description).
- e.g.,
BT::InputPort<std::string>("twist_topic")
-
- When the XML loader meets a tag such as:
<Action ID="FixedStandoffOrbit" point_cloud_topic="/points" …/>
- When the XML loader meets a tag such as:
- If the name exists and the string in XML can be converted to the declared C++ type (double, int, bool, std::string, custom structs…), the attribute becomes the runtime value of that port.
- Inside your node you call
getInput<T>("port_name")
. That function pulls the string from the blackboard, converts it to T and returns it as aBT::Expected<T>
(so you can handle missing / malformed data).
- e.g.,
Nodes
- A
CoroAction
is to pause, send an action goal, wait, get an action result, resume. - destructor order:
- the dtor body 2.members in a reverse order
Quirks & Known Bugs
Do NOT put a tf_listener in init()
(Till ROS Humble)
This is not a BT bug, yet a bug in TransformListener
. The call chain (on the same thread) is:
1
FixedStandoffOrbit::init() -> initialize a tf_listener
The issue is that an initialized tf_listener may cause a hanging issue if destruction comes too soon. Here is an issue report detailing this issue. Here’s why in summary:
Currently, the tf_listener
creates its own SingleThreadedExecutor
and spin the executor on a separate thread.
1
2
3
4
5
6
7
8
9
10
11
12
13
14
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
auto run_func =
[executor](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
executor->add_node(node_base_interface);
executor->spin();
executor->remove_node(node_base_interface);
};
dedicated_listener_thread_ = thread_ptr(
new std::thread(run_func, node_base_interface),
[executor](std::thread * t) {
executor->cancel();
t->join();
delete t;
});
In the case where the dedicated_listener_thread_
does not get to start before main calls the destructor (and tries to join the thread), the destructor hangs because dedicated_listener_thread_
is still running.
- main thread creates
dedicated_listener_thread_
- main thread perform all its jobs and
TransformListener
destructor - Main thread in TransformListener destructor calls
executor->cancel()
which setsexecutor.spinning = false
- Main thread waits for
dedicated_listener_thread_
to finish - Dedicated thread starts running and calls
executor->spin()
- Dedicated thread at the beginning of
executor->spin()
setsexecutor.spinning = true
- Dedicated thread is spinning waiting for messages or cancel which will not happen because main thread is blocked in
t->join();