Skip to content

Commit a9fbcac

Browse files
authored
planning_attempts -> max_solutions (#143)
The parameter describes the maximum number of found solutions before further planning is aborted.
1 parent f12cc0c commit a9fbcac

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

demo/config/panda_config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
# Total planning attempts
2-
planning_attempts: 10
2+
max_solutions: 10
33

44
# Planning group and link names
55
arm_group_name: "panda_arm"

demo/src/pick_place_task.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -419,10 +419,10 @@ void PickPlaceTask::init() {
419419
bool PickPlaceTask::plan() {
420420
ROS_INFO_NAMED(LOGNAME, "Start searching for task solutions");
421421
ros::NodeHandle pnh("~");
422-
int planning_attempts = pnh.param<int>("planning_attempts", 10);
422+
int max_solutions = pnh.param<int>("max_solutions", 10);
423423

424424
try {
425-
task_->plan(planning_attempts);
425+
task_->plan(max_solutions);
426426
} catch (InitStageException& e) {
427427
ROS_ERROR_STREAM_NAMED(LOGNAME, "Initialization failed: " << e);
428428
return false;

0 commit comments

Comments
 (0)