Skip to content

Commit ee14adc

Browse files
tonynajjarmasf7g
authored andcommitted
Change max_cost default to 254 (ros-navigation#5256)
Signed-off-by: Tony Najjar <[email protected]>
1 parent 797a28b commit ee14adc

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ IsPathValidCondition::IsPathValidCondition(
2424
const std::string & condition_name,
2525
const BT::NodeConfiguration & conf)
2626
: BT::ConditionNode(condition_name, conf),
27-
max_cost_(253), consider_unknown_as_obstacle_(false)
27+
max_cost_(254), consider_unknown_as_obstacle_(false)
2828
{
2929
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
3030
client_ = node_->create_client<nav2_msgs::srv::IsPathValid>("is_path_valid");

nav2_msgs/srv/IsPathValid.srv

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#Determine if the current path is still valid
22

33
nav_msgs/Path path
4-
uint8 max_cost 253
4+
uint8 max_cost 254
55
bool consider_unknown_as_obstacle false
66
int32 num_points_to_validate 0 # 0 - validate whole path, >0 - validate N points from start, <0 - do not validate N points from end
77
---

0 commit comments

Comments
 (0)