Skip to content

Commit f9ed2dc

Browse files
committed
Add createROSInterfaces()
Signed-off-by: Tatsuro Sakaguchi <tatsuro.sakaguchi@g.softbank.co.jp>
1 parent c65bdfe commit f9ed2dc

20 files changed

+128
-24
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp

Lines changed: 19 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -50,12 +50,6 @@ class BtServiceNode : public BT::ActionNodeBase
5050
: BT::ActionNodeBase(service_node_name, conf), service_name_(service_name), service_node_name_(
5151
service_node_name)
5252
{
53-
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
54-
callback_group_ = node_->create_callback_group(
55-
rclcpp::CallbackGroupType::MutuallyExclusive,
56-
false);
57-
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
58-
5953
// Get the required items from the blackboard
6054
auto bt_loop_duration =
6155
config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
@@ -67,11 +61,7 @@ class BtServiceNode : public BT::ActionNodeBase
6761
max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
6862

6963
// Now that we have node_ to use, create the service client for this BT service
70-
getInput("service_name", service_name_);
71-
service_client_ = node_->create_client<ServiceT>(
72-
service_name_,
73-
rclcpp::SystemDefaultsQoS(),
74-
callback_group_);
64+
createROSInterfaces();
7565

7666
// Make a request for the service without parameter
7767
request_ = std::make_shared<typename ServiceT::Request>();
@@ -101,6 +91,24 @@ class BtServiceNode : public BT::ActionNodeBase
10191
{
10292
}
10393

94+
/**
95+
* @brief Function to create ROS interfaces
96+
*/
97+
void createROSInterfaces()
98+
{
99+
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
100+
callback_group_ = node_->create_callback_group(
101+
rclcpp::CallbackGroupType::MutuallyExclusive,
102+
false);
103+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
104+
105+
getInput("service_name", service_name_);
106+
service_client_ = node_->create_client<ServiceT>(
107+
service_name_,
108+
rclcpp::SystemDefaultsQoS(),
109+
callback_group_);
110+
}
111+
104112
/**
105113
* @brief Any subclass of BtServiceNode that accepts parameters must provide a
106114
* providedPorts method and call providedBasicPorts in it.

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,11 @@ class ControllerSelector : public BT::SyncActionNode
7171
}
7272

7373
private:
74+
/**
75+
* @brief Function to create ROS interfaces
76+
*/
77+
void createROSInterfaces();
78+
7479
/**
7580
* @brief Function to perform some user-defined operation on tick
7681
*/

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,11 @@ class GoalCheckerSelector : public BT::SyncActionNode
7171
}
7272

7373
private:
74+
/**
75+
* @brief Function to create ROS interfaces
76+
*/
77+
void createROSInterfaces();
78+
7479
/**
7580
* @brief Function to perform some user-defined operation on tick
7681
*/

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,11 @@ class PlannerSelector : public BT::SyncActionNode
7171
}
7272

7373
private:
74+
/**
75+
* @brief Function to create ROS interfaces
76+
*/
77+
void createROSInterfaces();
78+
7479
/**
7580
* @brief Function to perform some user-defined operation on tick
7681
*/

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,11 @@ class ProgressCheckerSelector : public BT::SyncActionNode
7070
}
7171

7272
private:
73+
/**
74+
* @brief Function to create ROS interfaces
75+
*/
76+
void createROSInterfaces();
77+
7378
/**
7479
* @brief Function to perform some user-defined operation on tick
7580
*/

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smoother_selector_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,11 @@ class SmootherSelector : public BT::SyncActionNode
7171
}
7272

7373
private:
74+
/**
75+
* @brief Function to create ROS interfaces
76+
*/
77+
void createROSInterfaces();
78+
7479
/**
7580
* @brief Function to perform some user-defined operation on tick
7681
*/

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,11 @@ class IsBatteryChargingCondition : public BT::ConditionNode
6363
}
6464

6565
private:
66+
/**
67+
* @brief Function to create ROS interfaces
68+
*/
69+
void createROSInterfaces();
70+
6671
/**
6772
* @brief Callback function for battery topic
6873
* @param msg Shared pointer to sensor_msgs::msg::BatteryState message

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

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,10 @@ class IsPathValidCondition : public BT::ConditionNode
6868
}
6969

7070
private:
71+
/**
72+
* @brief Function to create ROS interfaces
73+
*/
74+
void createROSInterfaces();
7175
rclcpp::Node::SharedPtr node_;
7276
rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
7377
// The timeout value while waiting for a response from the

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,10 @@ class IsStuckCondition : public BT::ConditionNode
8484
static BT::PortsList providedPorts() {return {};}
8585

8686
private:
87+
/**
88+
* @brief Function to create ROS interfaces
89+
*/
90+
void createROSInterfaces();
8791
// The node that will be used for any ROS operations
8892
rclcpp::Node::SharedPtr node_;
8993
rclcpp::CallbackGroup::SharedPtr callback_group_;

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,10 @@ class GoalUpdater : public BT::DecoratorNode
6363
}
6464

6565
private:
66+
/**
67+
* @brief Function to create ROS interfaces
68+
*/
69+
void createROSInterfaces();
6670
/**
6771
* @brief The main override required by a BT action
6872
* @return BT::NodeStatus Status of tick execution

0 commit comments

Comments
 (0)