Skip to content

Commit 25d7299

Browse files
authored
update documentation (#43)
1 parent d93c86d commit 25d7299

File tree

1 file changed

+12
-12
lines changed

1 file changed

+12
-12
lines changed

docs/ros2_integration.md

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -48,18 +48,17 @@ should not worry about creating a separate thread.
4848
`TreeNode::halt()` and build reactive behaviors.
4949

5050
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).
5852

5953
To create a BT Action that invokes this ROS Action:
6054

6155
```cpp
6256
#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>;
6362

6463
using namespace BT;
6564

@@ -99,7 +98,7 @@ public:
9998
for (auto number : wr.result->sequence) {
10099
ss << number << " ";
101100
}
102-
RCLCPP_INFO(node_->get_logger(), ss.str().c_str());
101+
RCLCPP_INFO(logger(), ss.str().c_str());
103102
return NodeStatus::SUCCESS;
104103
}
105104

@@ -110,7 +109,7 @@ public:
110109
// If not overridden, it will return FAILURE by default.
111110
virtual NodeStatus onFailure(ActionNodeErrorCode error) override
112111
{
113-
RCLCPP_ERROR(node_->get_logger(), "Error: %d", error);
112+
RCLCPP_ERROR(logger(), "Error: %d", error);
114113
return NodeStatus::FAILURE;
115114
}
116115

@@ -128,7 +127,7 @@ public:
128127
for (auto number : feedback->partial_sequence) {
129128
ss << number << " ";
130129
}
131-
RCLCPP_INFO(node_->get_logger(), ss.str().c_str());
130+
RCLCPP_INFO(logger(), ss.str().c_str());
132131
return NodeStatus::RUNNING;
133132
}
134133
};
@@ -163,6 +162,7 @@ The example below is based on the
163162

164163
```cpp
165164
#include <behaviortree_ros2/bt_service_node.hpp>
165+
#include "example_interfaces/srv/add_two_ints.hpp"
166166

167167
using AddTwoInts = example_interfaces::srv::AddTwoInts;
168168
using namespace BT;
@@ -203,7 +203,7 @@ class AddTwoIntsNode: public RosServiceNode<AddTwoInts>
203203
// It must return SUCCESS or FAILURE
204204
NodeStatus onResponseReceived(const Response::SharedPtr& response) override
205205
{
206-
RCLCPP_INFO(node_->get_logger(), "Sum: %ld", response->sum);
206+
RCLCPP_INFO(logger(), "Sum: %ld", response->sum);
207207
return NodeStatus::SUCCESS;
208208
}
209209

@@ -214,7 +214,7 @@ class AddTwoIntsNode: public RosServiceNode<AddTwoInts>
214214
// If not overridden, it will return FAILURE by default.
215215
virtual NodeStatus onFailure(ServiceNodeErrorCode error) override
216216
{
217-
RCLCPP_ERROR(node_->get_logger(), "Error: %d", error);
217+
RCLCPP_ERROR(logger(), "Error: %d", error);
218218
return NodeStatus::FAILURE;
219219
}
220220
};

0 commit comments

Comments
 (0)