Skip to content

Commit 8ed1301

Browse files
papertowel123jwallace42
authored andcommitted
BT nodes not able to accept parameter values (ros-navigation#3988)
* fix simple cases * fix on_tick type in drive_on_heading node * fix linting and fixed other nodes * Revert "fix linting and fixed other nodes" This reverts commit c1cd575. * fix linting * fixes for subscription cases in action nodes * fixes in condition nodes * fix input usage * fix uncrustify * . * fix typo in back_up_action.cpp * fix in drive_on_heading_action * remove unnecessary first_use variables * typo * typo * typo * fixed typos * move initialize() method above tick() * revert changes in truncate_path_action node * revert changes in case of creating subscription in constructor * remove global_frame_ in remove_passed_goals_action node * changes in is_path_valid and rate_controller nodes * change bt_cancel_action node * change bt_action_node * add xml_tag parameter * revert changes in bt_action and bt_cancel_action nodes * pre-commit * . Signed-off-by: gg <josho.wallace@gmail.com>
1 parent dbb631e commit 8ed1301

28 files changed

+234
-32
lines changed

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,11 @@ class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTele
6464
*/
6565
BT::NodeStatus on_cancelled() override;
6666

67+
/**
68+
* @brief Function to read parameters and initialize class variables
69+
*/
70+
void initialize();
71+
6772
/**
6873
* @brief Creates list of BT ports
6974
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -81,6 +86,7 @@ class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTele
8186

8287
private:
8388
bool is_recovery_;
89+
bool initialized_;
8490
};
8591

8692
} // namespace nav2_behavior_tree

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,11 @@ class BackUpAction : public BtActionNode<nav2_msgs::action::BackUp>
6464
*/
6565
BT::NodeStatus on_cancelled() override;
6666

67+
/**
68+
* @brief Function to read parameters and initialize class variables
69+
*/
70+
void initialize();
71+
6772
/**
6873
* @brief Creates list of BT ports
6974
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -79,6 +84,9 @@ class BackUpAction : public BtActionNode<nav2_msgs::action::BackUp>
7984
"error_code_id", "The back up behavior server error code")
8085
});
8186
}
87+
88+
private:
89+
bool initialized_;
8290
};
8391

8492
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,11 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
4343
const std::string & action_name,
4444
const BT::NodeConfiguration & conf);
4545

46+
/**
47+
* @brief Function to read parameters and initialize class variables
48+
*/
49+
void initialize();
50+
4651
/**
4752
* @brief Creates list of BT ports
4853
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -59,6 +64,11 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
5964
});
6065
}
6166

67+
/**
68+
* @brief Function to perform some user-defined operation on tick
69+
*/
70+
void on_tick() override;
71+
6272
/**
6373
* @brief Function to perform some user-defined operation upon successful completion of the action
6474
*/
@@ -73,6 +83,9 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
7383
* @brief Function to perform some user-defined operation upon cancellation of the action
7484
*/
7585
BT::NodeStatus on_cancelled() override;
86+
87+
private:
88+
bool initalized_;
7689
};
7790

7891
} // namespace nav2_behavior_tree

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

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,10 @@ class RemovePassedGoals : public BT::ActionNodeBase
3636
const std::string & xml_tag_name,
3737
const BT::NodeConfiguration & conf);
3838

39+
/**
40+
* @brief Function to read parameters and initialize class variables
41+
*/
42+
void initialize();
3943

4044
static BT::PortsList providedPorts()
4145
{
@@ -56,6 +60,7 @@ class RemovePassedGoals : public BT::ActionNodeBase
5660
double transform_tolerance_;
5761
std::shared_ptr<tf2_ros::Buffer> tf_;
5862
std::string robot_base_frame_;
63+
bool initialized_;
5964
};
6065

6166
} // namespace nav2_behavior_tree

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,11 @@ class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
4848
*/
4949
void on_tick() override;
5050

51+
/**
52+
* @brief Function to read parameters and initialize class variables
53+
*/
54+
void initialize();
55+
5156
/**
5257
* @brief Creates list of BT ports
5358
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -81,6 +86,7 @@ class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
8186

8287
private:
8388
bool is_recovery_;
89+
bool initialized_;
8490
};
8591

8692
} // namespace nav2_behavior_tree

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,11 @@ class WaitAction : public BtActionNode<nav2_msgs::action::Wait>
4545
*/
4646
void on_tick() override;
4747

48+
/**
49+
* @brief Function to read parameters and initialize class variables
50+
*/
51+
void initialize();
52+
4853
/**
4954
* @brief Creates list of BT ports
5055
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -56,6 +61,9 @@ class WaitAction : public BtActionNode<nav2_msgs::action::Wait>
5661
BT::InputPort<double>("wait_duration", 1.0, "Wait time")
5762
});
5863
}
64+
65+
private:
66+
bool initialized_;
5967
};
6068

6169
} // namespace nav2_behavior_tree

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,11 @@ class DistanceTraveledCondition : public BT::ConditionNode
5252
*/
5353
BT::NodeStatus tick() override;
5454

55+
/**
56+
* @brief Function to read parameters and initialize class variables
57+
*/
58+
void initialize();
59+
5560
/**
5661
* @brief Creates list of BT ports
5762
* @return BT::PortsList Containing node-specific ports
@@ -74,6 +79,7 @@ class DistanceTraveledCondition : public BT::ConditionNode
7479
double distance_;
7580
double transform_tolerance_;
7681
std::string global_frame_, robot_base_frame_;
82+
bool initialized_;
7783
};
7884

7985
} // namespace nav2_behavior_tree

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,11 @@ class IsBatteryLowCondition : public BT::ConditionNode
5151
*/
5252
BT::NodeStatus tick() override;
5353

54+
/**
55+
* @brief Function to read parameters and initialize class variables
56+
*/
57+
void initialize();
58+
5459
/**
5560
* @brief Creates list of BT ports
5661
* @return BT::PortsList Containing node-specific ports
@@ -81,6 +86,7 @@ class IsBatteryLowCondition : public BT::ConditionNode
8186
double min_battery_;
8287
bool is_voltage_;
8388
bool is_battery_low_;
89+
bool initialized_;
8490
};
8591

8692
} // namespace nav2_behavior_tree

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,11 @@ class IsPathValidCondition : public BT::ConditionNode
5050
*/
5151
BT::NodeStatus tick() override;
5252

53+
/**
54+
* @brief Function to read parameters and initialize class variables
55+
*/
56+
void initialize();
57+
5358
/**
5459
* @brief Creates list of BT ports
5560
* @return BT::PortsList Containing node-specific ports
@@ -68,6 +73,7 @@ class IsPathValidCondition : public BT::ConditionNode
6873
// The timeout value while waiting for a responce from the
6974
// is path valid service
7075
std::chrono::milliseconds server_timeout_;
76+
bool initialized_;
7177
};
7278

7379
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/time_expired_condition.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,11 @@ class TimeExpiredCondition : public BT::ConditionNode
4848
*/
4949
BT::NodeStatus tick() override;
5050

51+
/**
52+
* @brief Function to read parameters and initialize class variables
53+
*/
54+
void initialize();
55+
5156
/**
5257
* @brief Creates list of BT ports
5358
* @return BT::PortsList Containing node-specific ports
@@ -63,6 +68,7 @@ class TimeExpiredCondition : public BT::ConditionNode
6368
rclcpp::Node::SharedPtr node_;
6469
rclcpp::Time start_;
6570
double period_;
71+
bool initialized_;
6672
};
6773

6874
} // namespace nav2_behavior_tree

0 commit comments

Comments
 (0)