Skip to content

Commit 1da25a3

Browse files
committed
spin without costmap
1 parent eac506a commit 1da25a3

File tree

5 files changed

+8
-1
lines changed

5 files changed

+8
-1
lines changed

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

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
6565
BT::InputPort<double>("spin_dist", 1.57, "Spin distance"),
6666
BT::InputPort<double>("time_allowance", 10.0, "Allowed time for spinning"),
6767
BT::InputPort<bool>("is_recovery", true, "True if recovery"),
68+
BT::InputPort<bool>("check_local_costmap", true, "Check local costmap for collisions"),
6869
BT::OutputPort<ActionResult::_error_code_type>(
6970
"error_code_id", "The spin behavior error code")
7071
});

nav2_behavior_tree/plugins/action/spin_action.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,9 @@ void SpinAction::initialize()
3737
goal_.target_yaw = dist;
3838
goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
3939
getInput("is_recovery", is_recovery_);
40+
bool check_local_costmap;
41+
getInput("check_local_costmap", check_local_costmap);
42+
goal_.check_local_costmap = check_local_costmap;
4043

4144
initialized_ = true;
4245
}

nav2_behaviors/include/nav2_behaviors/plugins/spin.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@ class Spin : public TimedBehavior<SpinAction>
9090
double prev_yaw_;
9191
double relative_yaw_;
9292
double simulate_ahead_time_;
93+
bool check_local_costmap_;
9394
rclcpp::Duration command_time_allowance_{0, 0};
9495
rclcpp::Time end_time_;
9596
};

nav2_behaviors/plugins/spin.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,7 @@ ResultStatus Spin::onRun(const std::shared_ptr<const SpinActionGoal> command)
9292

9393
command_time_allowance_ = command->time_allowance;
9494
end_time_ = steady_clock_.now() + command_time_allowance_;
95+
check_local_costmap_ = command->check_local_costmap;
9596

9697
return ResultStatus{Status::SUCCEEDED, SpinActionGoal::NONE};
9798
}
@@ -146,7 +147,7 @@ ResultStatus Spin::onCycleUpdate()
146147
pose2d.y = current_pose.pose.position.y;
147148
pose2d.theta = tf2::getYaw(current_pose.pose.orientation);
148149

149-
if (!isCollisionFree(relative_yaw_, cmd_vel.get(), pose2d)) {
150+
if (check_local_costmap_ && !isCollisionFree(relative_yaw_, cmd_vel.get(), pose2d)) {
150151
stopRobot();
151152
RCLCPP_WARN(logger_, "Collision Ahead - Exiting Spin");
152153
return ResultStatus{Status::FAILED, SpinActionGoal::COLLISION_AHEAD};

nav2_msgs/action/Spin.action

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ uint16 COLLISION_AHEAD=703
99
#goal definition
1010
float32 target_yaw
1111
builtin_interfaces/Duration time_allowance
12+
bool check_local_costmap
1213
---
1314
#result definition
1415
builtin_interfaces/Duration total_elapsed_time

0 commit comments

Comments
 (0)