mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
planning_attempts -> max_solutions (#143)
The parameter describes the maximum number of found solutions before further planning is aborted.
This commit is contained in:
parent
f12cc0c127
commit
a9fbcac31f
@ -1,5 +1,5 @@
|
|||||||
# Total planning attempts
|
# Total planning attempts
|
||||||
planning_attempts: 10
|
max_solutions: 10
|
||||||
|
|
||||||
# Planning group and link names
|
# Planning group and link names
|
||||||
arm_group_name: "panda_arm"
|
arm_group_name: "panda_arm"
|
||||||
|
|||||||
@ -419,10 +419,10 @@ void PickPlaceTask::init() {
|
|||||||
bool PickPlaceTask::plan() {
|
bool PickPlaceTask::plan() {
|
||||||
ROS_INFO_NAMED(LOGNAME, "Start searching for task solutions");
|
ROS_INFO_NAMED(LOGNAME, "Start searching for task solutions");
|
||||||
ros::NodeHandle pnh("~");
|
ros::NodeHandle pnh("~");
|
||||||
int planning_attempts = pnh.param<int>("planning_attempts", 10);
|
int max_solutions = pnh.param<int>("max_solutions", 10);
|
||||||
|
|
||||||
try {
|
try {
|
||||||
task_->plan(planning_attempts);
|
task_->plan(max_solutions);
|
||||||
} catch (InitStageException& e) {
|
} catch (InitStageException& e) {
|
||||||
ROS_ERROR_STREAM_NAMED(LOGNAME, "Initialization failed: " << e);
|
ROS_ERROR_STREAM_NAMED(LOGNAME, "Initialization failed: " << e);
|
||||||
return false;
|
return false;
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user