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
f4cd7d5b85
commit
39eeae4a1b
@ -35,6 +35,8 @@
|
||||
|
||||
/* Authors: Michael Goerner, Luca Lach, Robert Haschke */
|
||||
|
||||
#include <chrono>
|
||||
|
||||
#include <moveit/task_constructor/stages/current_state.h>
|
||||
#include <moveit/task_constructor/storage.h>
|
||||
#include <moveit_msgs/srv/get_planning_scene.hpp>
|
||||
@ -47,13 +49,16 @@ namespace moveit {
|
||||
namespace task_constructor {
|
||||
namespace stages {
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
constexpr std::chrono::duration<double> DEFAULT_TIMEOUT = 3s;
|
||||
|
||||
static const rclcpp::Logger LOGGER = rclcpp::get_logger("CurrentState");
|
||||
|
||||
CurrentState::CurrentState(const std::string& name) : Generator(name) {
|
||||
auto& p = properties();
|
||||
Property& timeout = p.property("timeout");
|
||||
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) {
|
||||
|
||||
Loading…
Reference in New Issue
Block a user