Skip to content

Commit

Permalink
set a non-infinite default timeout in CurrentState stage (#491)
Browse files Browse the repository at this point in the history
Co-authored-by: Mario Prats <[email protected]>
  • Loading branch information
sjahr and marioprats authored Oct 6, 2023
1 parent f4cd7d5 commit 39eeae4
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion core/src/stages/current_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand All @@ -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) {
Expand Down

0 comments on commit 39eeae4

Please sign in to comment.