planning_attempts -> max_solutions (#143)

The parameter describes the maximum number of found solutions before further planning is aborted.
This commit is contained in:
Michael Görner 2020-03-10 15:00:22 +01:00 committed by GitHub
parent f12cc0c127
commit a9fbcac31f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 3 additions and 3 deletions

View File

@ -1,5 +1,5 @@
# Total planning attempts
planning_attempts: 10
max_solutions: 10
# Planning group and link names
arm_group_name: "panda_arm"

View File

@ -419,10 +419,10 @@ void PickPlaceTask::init() {
bool PickPlaceTask::plan() {
ROS_INFO_NAMED(LOGNAME, "Start searching for task solutions");
ros::NodeHandle pnh("~");
int planning_attempts = pnh.param<int>("planning_attempts", 10);
int max_solutions = pnh.param<int>("max_solutions", 10);
try {
task_->plan(planning_attempts);
task_->plan(max_solutions);
} catch (InitStageException& e) {
ROS_ERROR_STREAM_NAMED(LOGNAME, "Initialization failed: " << e);
return false;