Skip to content

Commit f0cf034

Browse files
authored
Expose distance controller frames to ports (#1741)
1 parent 21e2fec commit f0cf034

File tree

2 files changed

+14
-4
lines changed

2 files changed

+14
-4
lines changed

‎nav2_behavior_tree/plugins/decorator/distance_controller.cpp‎

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -35,9 +35,13 @@ DistanceController::DistanceController(
3535
const BT::NodeConfiguration & conf)
3636
: BT::DecoratorNode(name, conf),
3737
distance_(1.0),
38+
global_frame_("map"),
39+
robot_base_frame_("base_link"),
3840
first_time_(false)
3941
{
4042
getInput("distance", distance_);
43+
getInput("global_frame", global_frame_);
44+
getInput("robot_base_frame", robot_base_frame_);
4145
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
4246
tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
4347
}
@@ -47,7 +51,7 @@ inline BT::NodeStatus DistanceController::tick()
4751
if (status() == BT::NodeStatus::IDLE) {
4852
// Reset the starting position since we're starting a new iteration of
4953
// the distance controller (moving from IDLE to RUNNING)
50-
if (!nav2_util::getCurrentPose(start_pose_, *tf_)) {
54+
if (!nav2_util::getCurrentPose(start_pose_, *tf_, global_frame_, robot_base_frame_)) {
5155
RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
5256
return BT::NodeStatus::FAILURE;
5357
}
@@ -58,7 +62,7 @@ inline BT::NodeStatus DistanceController::tick()
5862

5963
// Determine distance travelled since we've started this iteration
6064
geometry_msgs::msg::PoseStamped current_pose;
61-
if (!nav2_util::getCurrentPose(current_pose, *tf_)) {
65+
if (!nav2_util::getCurrentPose(current_pose, *tf_, global_frame_, robot_base_frame_)) {
6266
RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
6367
return BT::NodeStatus::FAILURE;
6468
}
@@ -81,7 +85,7 @@ inline BT::NodeStatus DistanceController::tick()
8185
return BT::NodeStatus::RUNNING;
8286

8387
case BT::NodeStatus::SUCCESS:
84-
if (!nav2_util::getCurrentPose(start_pose_, *tf_)) {
88+
if (!nav2_util::getCurrentPose(start_pose_, *tf_, global_frame_, robot_base_frame_)) {
8589
RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
8690
return BT::NodeStatus::FAILURE;
8791
}

‎nav2_behavior_tree/plugins/decorator/distance_controller.hpp‎

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,9 @@ class DistanceController : public BT::DecoratorNode
3838
static BT::PortsList providedPorts()
3939
{
4040
return {
41-
BT::InputPort<double>("distance", 1.0, "Distance")
41+
BT::InputPort<double>("distance", 1.0, "Distance"),
42+
BT::InputPort<std::string>("global_frame", std::string("map"), "Global frame"),
43+
BT::InputPort<std::string>("robot_base_frame", std::string("base_link"), "Robot base frame")
4244
};
4345
}
4446

@@ -51,6 +53,10 @@ class DistanceController : public BT::DecoratorNode
5153

5254
geometry_msgs::msg::PoseStamped start_pose_;
5355
double distance_;
56+
57+
std::string global_frame_;
58+
std::string robot_base_frame_;
59+
5460
bool first_time_;
5561
};
5662

0 commit comments

Comments
 (0)