Skip to content

Commit b0f388a

Browse files
sjahrmarioprats
authored andcommitted
Set a non-infinite default timeout in CurrentState stage (moveit#491)
Co-authored-by: Mario Prats <[email protected]>
1 parent 48ca3d4 commit b0f388a

File tree

1 file changed

+6
-1
lines changed

1 file changed

+6
-1
lines changed

core/src/stages/current_state.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,8 @@
3535

3636
/* Authors: Michael Goerner, Luca Lach, Robert Haschke */
3737

38+
#include <chrono>
39+
3840
#include <moveit/task_constructor/stages/current_state.h>
3941
#include <moveit/task_constructor/storage.h>
4042
#include <moveit_msgs/GetPlanningScene.h>
@@ -47,11 +49,14 @@ namespace moveit {
4749
namespace task_constructor {
4850
namespace stages {
4951

52+
using namespace std::chrono_literals;
53+
constexpr std::chrono::duration<double> DEFAULT_TIMEOUT = 3s;
54+
5055
CurrentState::CurrentState(const std::string& name) : Generator(name) {
5156
auto& p = properties();
5257
Property& timeout = p.property("timeout");
5358
timeout.setDescription("max time to wait for get_planning_scene service");
54-
timeout.setValue(-1.0);
59+
timeout.setValue(DEFAULT_TIMEOUT.count());
5560
}
5661

5762
void CurrentState::init(const moveit::core::RobotModelConstPtr& robot_model) {

0 commit comments

Comments
 (0)