Skip to content

Commit ff526cb

Browse files
committed
Pass IDLE to on_tick, use that for initialize condition
Signed-off-by: redvinaa <redvinaa@gmail.com>
1 parent 6b2e244 commit ff526cb

25 files changed

+27
-73
lines changed

‎nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp‎

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -191,15 +191,15 @@ class BtActionNode : public BT::ActionNodeBase
191191
{
192192
// first step to be done only at the beginning of the Action
193193
if (!BT::isStatusActive(status())) {
194-
// setting the status to RUNNING to notify the BT Loggers (if any)
195-
setStatus(BT::NodeStatus::RUNNING);
196-
197194
// reset the flag to send the goal or not, allowing the user the option to set it in on_tick
198195
should_send_goal_ = true;
199196

200197
// user defined callback, may modify "should_send_goal_".
201198
on_tick();
202199

200+
// setting the status to RUNNING to notify the BT Loggers (if any)
201+
setStatus(BT::NodeStatus::RUNNING);
202+
203203
if (!should_send_goal_) {
204204
return BT::NodeStatus::FAILURE;
205205
}

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,6 @@ class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTele
8686

8787
private:
8888
bool is_recovery_;
89-
bool initialized_;
9089
};
9190

9291
} // namespace nav2_behavior_tree

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

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -84,9 +84,6 @@ class BackUpAction : public BtActionNode<nav2_msgs::action::BackUp>
8484
"error_code_id", "The back up behavior server error code")
8585
});
8686
}
87-
88-
private:
89-
bool initialized_;
9087
};
9188

9289
} // namespace nav2_behavior_tree

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,6 @@ class RemovePassedGoals : public BT::ActionNodeBase
6161
double transform_tolerance_;
6262
std::shared_ptr<tf2_ros::Buffer> tf_;
6363
std::string robot_base_frame_;
64-
bool initialized_;
6564
};
6665

6766
} // namespace nav2_behavior_tree

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,6 @@ class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
8686

8787
private:
8888
bool is_recovery_;
89-
bool initialized_;
9089
};
9190

9291
} // namespace nav2_behavior_tree

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

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,9 +61,6 @@ class WaitAction : public BtActionNode<nav2_msgs::action::Wait>
6161
BT::InputPort<double>("wait_duration", 1.0, "Wait time")
6262
});
6363
}
64-
65-
private:
66-
bool initialized_;
6764
};
6865

6966
} // namespace nav2_behavior_tree

‎nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp‎

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,6 @@ class DistanceTraveledCondition : public BT::ConditionNode
8080
double distance_;
8181
double transform_tolerance_;
8282
std::string global_frame_, robot_base_frame_;
83-
bool initialized_;
8483
};
8584

8685
} // namespace nav2_behavior_tree

‎nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp‎

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,6 @@ class GoalReachedCondition : public BT::ConditionNode
9090
rclcpp::Node::SharedPtr node_;
9191
std::shared_ptr<tf2_ros::Buffer> tf_;
9292

93-
bool initialized_;
9493
double goal_reached_tol_;
9594
double transform_tolerance_;
9695
std::string robot_base_frame_;

‎nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp‎

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,6 @@ class IsBatteryLowCondition : public BT::ConditionNode
8686
double min_battery_;
8787
bool is_voltage_;
8888
bool is_battery_low_;
89-
bool initialized_;
9089
};
9190

9291
} // namespace nav2_behavior_tree

‎nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp‎

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,6 @@ class IsPathValidCondition : public BT::ConditionNode
7373
// The timeout value while waiting for a responce from the
7474
// is path valid service
7575
std::chrono::milliseconds server_timeout_;
76-
bool initialized_;
7776
};
7877

7978
} // namespace nav2_behavior_tree

0 commit comments

Comments
 (0)