@@ -48,18 +48,17 @@ should not worry about creating a separate thread.
48
48
` TreeNode::halt() ` and build reactive behaviors.
49
49
50
50
Let's consider, for instance, the "Fibonacci" action client described in the
51
- [ official C++ tutorial] ( https://docs.ros.org/en/humble/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.html#writing-an-action-client ) :
52
-
53
- ``` cpp
54
- // let's define these, for brevity
55
- using Fibonacci = action_tutorials_interfaces::action::Fibonacci;
56
- using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle<Fibonacci>;
57
- ```
51
+ [ official C++ tutorial] ( https://docs.ros.org/en/humble/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.html#writing-an-action-client ) .
58
52
59
53
To create a BT Action that invokes this ROS Action:
60
54
61
55
``` cpp
62
56
#include < behaviortree_ros2/bt_action_node.hpp>
57
+ #include " action_tutorials_interfaces/action/fibonacci.hpp"
58
+
59
+ // let's define these, for brevity
60
+ using Fibonacci = action_tutorials_interfaces::action::Fibonacci;
61
+ using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle<Fibonacci>;
63
62
64
63
using namespace BT ;
65
64
@@ -99,7 +98,7 @@ public:
99
98
for (auto number : wr.result->sequence) {
100
99
ss << number << " ";
101
100
}
102
- RCLCPP_INFO(node _ ->get_logger (), ss.str().c_str());
101
+ RCLCPP_INFO(logger (), ss.str().c_str());
103
102
return NodeStatus::SUCCESS;
104
103
}
105
104
@@ -110,7 +109,7 @@ public:
110
109
// If not overridden, it will return FAILURE by default.
111
110
virtual NodeStatus onFailure(ActionNodeErrorCode error) override
112
111
{
113
- RCLCPP_ERROR(node _ ->get_logger (), "Error: %d", error);
112
+ RCLCPP_ERROR(logger (), "Error: %d", error);
114
113
return NodeStatus::FAILURE;
115
114
}
116
115
@@ -128,7 +127,7 @@ public:
128
127
for (auto number : feedback->partial_sequence) {
129
128
ss << number << " ";
130
129
}
131
- RCLCPP_INFO(node _ ->get_logger (), ss.str().c_str());
130
+ RCLCPP_INFO(logger (), ss.str().c_str());
132
131
return NodeStatus::RUNNING;
133
132
}
134
133
};
@@ -163,6 +162,7 @@ The example below is based on the
163
162
164
163
``` cpp
165
164
#include < behaviortree_ros2/bt_service_node.hpp>
165
+ #include " example_interfaces/srv/add_two_ints.hpp"
166
166
167
167
using AddTwoInts = example_interfaces::srv::AddTwoInts;
168
168
using namespace BT ;
@@ -203,7 +203,7 @@ class AddTwoIntsNode: public RosServiceNode<AddTwoInts>
203
203
// It must return SUCCESS or FAILURE
204
204
NodeStatus onResponseReceived(const Response::SharedPtr& response) override
205
205
{
206
- RCLCPP_INFO(node _ ->get_logger (), "Sum: %ld", response->sum);
206
+ RCLCPP_INFO(logger (), "Sum: %ld", response->sum);
207
207
return NodeStatus::SUCCESS;
208
208
}
209
209
@@ -214,7 +214,7 @@ class AddTwoIntsNode: public RosServiceNode<AddTwoInts>
214
214
// If not overridden, it will return FAILURE by default.
215
215
virtual NodeStatus onFailure(ServiceNodeErrorCode error) override
216
216
{
217
- RCLCPP_ERROR(node _ ->get_logger (), "Error: %d", error);
217
+ RCLCPP_ERROR(logger (), "Error: %d", error);
218
218
return NodeStatus::FAILURE;
219
219
}
220
220
};
0 commit comments