From 80ae01dccaf025741ad7ddd4eeedcf20fba16859 Mon Sep 17 00:00:00 2001 From: v4hn Date: Mon, 26 Feb 2018 14:14:09 +0100 Subject: [PATCH] expose timeout property as typed setter --- core/include/moveit/task_constructor/stages/connect.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/core/include/moveit/task_constructor/stages/connect.h b/core/include/moveit/task_constructor/stages/connect.h index 7a9ec275..566d3489 100644 --- a/core/include/moveit/task_constructor/stages/connect.h +++ b/core/include/moveit/task_constructor/stages/connect.h @@ -49,6 +49,10 @@ class Connect : public Connecting { public: Connect(std::string name, const solvers::PlannerInterfacePtr &planner); + void setTimeout(const ros::Duration& timeout){ + setProperty("timeout", timeout.toSec()); + } + void setPathConstraints(moveit_msgs::Constraints path_constraints){ setProperty("path_constraints", std::move(path_constraints)); }