diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index 35c6938f0d3..163742a2f47 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -67,10 +67,10 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer // ROSInitializer is constructed first, and ensures ros::init() was called, if // needed MoveGroupInterfaceWrapper(const std::string& group_name, const std::string& robot_description, - const std::string& ns = "") + const std::string& ns = "", double wait_for_servers = 5.0) : py_bindings_tools::ROScppInitializer() , MoveGroupInterface(Options(group_name, robot_description, ros::NodeHandle(ns)), - std::shared_ptr(), ros::WallDuration(5, 0)) + std::shared_ptr(), ros::WallDuration(wait_for_servers)) { }