Skip to content

Commit ec80f36

Browse files
committed
Update server_timeout to 20ms and inherit BtServiceNode from BT::ActionNodeBase
Signed-off-by: Sarthak Mittal <[email protected]>
1 parent ade30aa commit ec80f36

21 files changed

+34
-28
lines changed

.gitignore

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,3 +46,7 @@ __pycache__/
4646
*.py[cod]
4747

4848
sphinx_doc/_build
49+
50+
# CLion artifacts
51+
.idea
52+
cmake-build-debug/

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ BtActionServer<ActionT>::BtActionServer(
5757
node->declare_parameter("bt_loop_duration", 10);
5858
}
5959
if (!node->has_parameter("default_server_timeout")) {
60-
node->declare_parameter("default_server_timeout", 10);
60+
node->declare_parameter("default_server_timeout", 20);
6161
}
6262
if (!node->has_parameter("enable_groot_monitoring")) {
6363
node->declare_parameter("enable_groot_monitoring", true);

nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ namespace nav2_behavior_tree
3131
* @tparam ServiceT Type of service
3232
*/
3333
template<class ServiceT>
34-
class BtServiceNode : public BT::SyncActionNode
34+
class BtServiceNode : public BT::ActionNodeBase
3535
{
3636
public:
3737
/**
@@ -42,7 +42,7 @@ class BtServiceNode : public BT::SyncActionNode
4242
BtServiceNode(
4343
const std::string & service_node_name,
4444
const BT::NodeConfiguration & conf)
45-
: BT::SyncActionNode(service_node_name, conf), service_node_name_(service_node_name)
45+
: BT::ActionNodeBase(service_node_name, conf), service_node_name_(service_node_name)
4646
{
4747
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
4848

@@ -118,6 +118,15 @@ class BtServiceNode : public BT::SyncActionNode
118118
return check_future();
119119
}
120120

121+
/**
122+
* @brief The other (optional) override required by a BT service.
123+
*/
124+
void halt() override
125+
{
126+
request_sent_ = false;
127+
setStatus(BT::NodeStatus::IDLE);
128+
}
129+
121130
/**
122131
* @brief Function to perform some user-defined operation on tick
123132
* Fill in service request with information if necessary

nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ class BackUpActionTestFixture : public ::testing::Test
6464
node_);
6565
config_->blackboard->set<std::chrono::milliseconds>(
6666
"server_timeout",
67-
std::chrono::milliseconds(10));
67+
std::chrono::milliseconds(20));
6868
config_->blackboard->set<std::chrono::milliseconds>(
6969
"bt_loop_duration",
7070
std::chrono::milliseconds(10));

nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp

Lines changed: 1 addition & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ class BTActionNodeTestFixture : public ::testing::Test
141141
config_->blackboard = BT::Blackboard::create();
142142
// Put items on the blackboard
143143
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
144-
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 10ms);
144+
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 20ms);
145145
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
146146
config_->blackboard->set<bool>("initial_pose_received", false);
147147

@@ -246,10 +246,6 @@ TEST_F(BTActionNodeTestFixture, test_server_timeout_success)
246246
// the BT should have succeeded
247247
EXPECT_EQ(result, BT::NodeStatus::SUCCESS);
248248

249-
// even though the goal is accepted in the first tick, due to some timing issues
250-
// the goal result is available in the next tick
251-
EXPECT_EQ(ticks, 2);
252-
253249
// checking the output fibonacci sequence
254250
EXPECT_EQ(sequence.size(), expected.size());
255251
for (size_t i = 0; i < expected.size(); ++i) {
@@ -350,9 +346,6 @@ TEST_F(BTActionNodeTestFixture, test_server_timeout_failure)
350346
// since the server timeout was smaller than the action server goal handling duration
351347
// the BT should have failed
352348
EXPECT_EQ(result, BT::NodeStatus::SUCCESS);
353-
354-
// takes 3 ticks waiting for the action server acknowledgement and 3 more ticks to get goal result
355-
EXPECT_EQ(ticks, 6);
356349
}
357350

358351
int main(int argc, char ** argv)

nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test
4949
node_);
5050
config_->blackboard->set<std::chrono::milliseconds>(
5151
"server_timeout",
52-
std::chrono::milliseconds(10));
52+
std::chrono::milliseconds(20));
5353
config_->blackboard->set<std::chrono::milliseconds>(
5454
"bt_loop_duration",
5555
std::chrono::milliseconds(10));

nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test
7272
node_);
7373
config_->blackboard->set<std::chrono::milliseconds>(
7474
"server_timeout",
75-
std::chrono::milliseconds(10));
75+
std::chrono::milliseconds(20));
7676
config_->blackboard->set<std::chrono::milliseconds>(
7777
"bt_loop_duration",
7878
std::chrono::milliseconds(10));

nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test
7070
node_);
7171
config_->blackboard->set<std::chrono::milliseconds>(
7272
"server_timeout",
73-
std::chrono::milliseconds(10));
73+
std::chrono::milliseconds(20));
7474
config_->blackboard->set<std::chrono::milliseconds>(
7575
"bt_loop_duration",
7676
std::chrono::milliseconds(10));

nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class FollowPathActionTestFixture : public ::testing::Test
6363
node_);
6464
config_->blackboard->set<std::chrono::milliseconds>(
6565
"server_timeout",
66-
std::chrono::milliseconds(10));
66+
std::chrono::milliseconds(20));
6767
config_->blackboard->set<std::chrono::milliseconds>(
6868
"bt_loop_duration",
6969
std::chrono::milliseconds(10));

nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test
6666
node_);
6767
config_->blackboard->set<std::chrono::milliseconds>(
6868
"server_timeout",
69-
std::chrono::milliseconds(10));
69+
std::chrono::milliseconds(20));
7070
config_->blackboard->set<std::chrono::milliseconds>(
7171
"bt_loop_duration",
7272
std::chrono::milliseconds(10));

0 commit comments

Comments
 (0)