mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
Set a non-infinite default timeout in CurrentState stage (#491)
Co-authored-by: Mario Prats <mario.prats@picknik.ai>
This commit is contained in:
parent
48ca3d46f6
commit
b0f388a88f
@ -35,6 +35,8 @@
|
|||||||
|
|
||||||
/* Authors: Michael Goerner, Luca Lach, Robert Haschke */
|
/* Authors: Michael Goerner, Luca Lach, Robert Haschke */
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
|
||||||
#include <moveit/task_constructor/stages/current_state.h>
|
#include <moveit/task_constructor/stages/current_state.h>
|
||||||
#include <moveit/task_constructor/storage.h>
|
#include <moveit/task_constructor/storage.h>
|
||||||
#include <moveit_msgs/GetPlanningScene.h>
|
#include <moveit_msgs/GetPlanningScene.h>
|
||||||
@ -47,11 +49,14 @@ namespace moveit {
|
|||||||
namespace task_constructor {
|
namespace task_constructor {
|
||||||
namespace stages {
|
namespace stages {
|
||||||
|
|
||||||
|
using namespace std::chrono_literals;
|
||||||
|
constexpr std::chrono::duration<double> DEFAULT_TIMEOUT = 3s;
|
||||||
|
|
||||||
CurrentState::CurrentState(const std::string& name) : Generator(name) {
|
CurrentState::CurrentState(const std::string& name) : Generator(name) {
|
||||||
auto& p = properties();
|
auto& p = properties();
|
||||||
Property& timeout = p.property("timeout");
|
Property& timeout = p.property("timeout");
|
||||||
timeout.setDescription("max time to wait for get_planning_scene service");
|
timeout.setDescription("max time to wait for get_planning_scene service");
|
||||||
timeout.setValue(-1.0);
|
timeout.setValue(DEFAULT_TIMEOUT.count());
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::init(const moveit::core::RobotModelConstPtr& robot_model) {
|
void CurrentState::init(const moveit::core::RobotModelConstPtr& robot_model) {
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user