Skip to content

Commit 63fc6a1

Browse files
In wait_action node change duration type from int to double (#3871)
* change duration tyype from int to double * change "1" to "1.0" as default wait_duration value * modify wait_action tests * fix * change int values to double in trees * add usage of Duration::from_seconds() * fix build failing issue * delete whitespace
1 parent 924f167 commit 63fc6a1

File tree

8 files changed

+15
-14
lines changed

8 files changed

+15
-14
lines changed

‎nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_action.hpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ class WaitAction : public BtActionNode<nav2_msgs::action::Wait>
5353
{
5454
return providedBasicPorts(
5555
{
56-
BT::InputPort<int>("wait_duration", 1, "Wait time")
56+
BT::InputPort<double>("wait_duration", 1.0, "Wait time")
5757
});
5858
}
5959
};

‎nav2_behavior_tree/plugins/action/wait_action.cpp‎

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
#include <string>
1616
#include <memory>
17+
#include <cmath>
1718

1819
#include "nav2_behavior_tree/plugins/action/wait_action.hpp"
1920

@@ -26,16 +27,16 @@ WaitAction::WaitAction(
2627
const BT::NodeConfiguration & conf)
2728
: BtActionNode<nav2_msgs::action::Wait>(xml_tag_name, action_name, conf)
2829
{
29-
int duration;
30+
double duration;
3031
getInput("wait_duration", duration);
3132
if (duration <= 0) {
3233
RCLCPP_WARN(
3334
node_->get_logger(), "Wait duration is negative or zero "
34-
"(%i). Setting to positive.", duration);
35+
"(%f). Setting to positive.", duration);
3536
duration *= -1;
3637
}
3738

38-
goal_.time.sec = duration;
39+
goal_.time = rclcpp::Duration::from_seconds(duration);
3940
}
4041

4142
void WaitAction::on_tick()

‎nav2_behavior_tree/test/plugins/action/test_wait_action.cpp‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -117,18 +117,18 @@ TEST_F(WaitActionTestFixture, test_ports)
117117
</root>)";
118118

119119
tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
120-
EXPECT_EQ(tree_->rootNode()->getInput<int>("wait_duration"), 1);
120+
EXPECT_EQ(tree_->rootNode()->getInput<double>("wait_duration"), 1.0);
121121

122122
xml_txt =
123123
R"(
124124
<root main_tree_to_execute = "MainTree" >
125125
<BehaviorTree ID="MainTree">
126-
<Wait wait_duration="10" />
126+
<Wait wait_duration="10.0" />
127127
</BehaviorTree>
128128
</root>)";
129129

130130
tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
131-
EXPECT_EQ(tree_->rootNode()->getInput<int>("wait_duration"), 10);
131+
EXPECT_EQ(tree_->rootNode()->getInput<double>("wait_duration"), 10.0);
132132
}
133133

134134
TEST_F(WaitActionTestFixture, test_tick)
@@ -137,7 +137,7 @@ TEST_F(WaitActionTestFixture, test_tick)
137137
R"(
138138
<root main_tree_to_execute = "MainTree" >
139139
<BehaviorTree ID="MainTree">
140-
<Wait wait_duration="-5"/>
140+
<Wait wait_duration="-5.0"/>
141141
</BehaviorTree>
142142
</root>)";
143143

‎nav2_bt_navigator/behavior_trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.xml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
3838
</Sequence>
3939
<Spin spin_dist="1.57"/>
40-
<Wait wait_duration="5"/>
40+
<Wait wait_duration="5.0"/>
4141
<BackUp backup_dist="0.30" backup_speed="0.05"/>
4242
</RoundRobin>
4343
</ReactiveFallback>

‎nav2_bt_navigator/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
3030
</Sequence>
3131
<Spin spin_dist="1.57" error_code_id="{spin_error_code}"/>
32-
<Wait wait_duration="5"/>
32+
<Wait wait_duration="5.0"/>
3333
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}"/>
3434
</RoundRobin>
3535
</ReactiveFallback>

‎nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
3939
</Sequence>
4040
<Spin spin_dist="1.57" error_code_id="{spin_error_code}"/>
41-
<Wait wait_duration="5"/>
41+
<Wait wait_duration="5.0"/>
4242
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_code_id}"/>
4343
</RoundRobin>
4444
</ReactiveFallback>

‎nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_goal_patience_and_recovery.xml‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
<RetryUntilSuccessful num_attempts="1">
2121
<SequenceStar name="CancelingControlAndWait">
2222
<CancelControl name="ControlCancel"/>
23-
<Wait wait_duration="5"/>
23+
<Wait wait_duration="5.0"/>
2424
</SequenceStar>
2525
</RetryUntilSuccessful>
2626
</PathLongerOnApproach>
@@ -38,7 +38,7 @@
3838
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
3939
</Sequence>
4040
<Spin spin_dist="1.57"/>
41-
<Wait wait_duration="5"/>
41+
<Wait wait_duration="5.0"/>
4242
<BackUp backup_dist="0.30" backup_speed="0.05"/>
4343
</RoundRobin>
4444
</ReactiveFallback>

‎nav2_bt_navigator/behavior_trees/navigate_w_recovery_and_replanning_only_if_path_becomes_invalid.xml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
3636
</Sequence>
3737
<Spin name="SpinRecovery" spin_dist="1.57"/>
38-
<Wait name="WaitRecovery" wait_duration="5"/>
38+
<Wait name="WaitRecovery" wait_duration="5.0"/>
3939
<BackUp name="BackUpRecovery" backup_dist="0.30" backup_speed="0.05"/>
4040
</RoundRobin>
4141
</ReactiveFallback>

0 commit comments

Comments
 (0)