Skip to content

Commit 5caf92c

Browse files
ymollardsussybot5258
authored andcommitted
SERVICE_CALL_TIMEOUT = 1 second is harsh 🥵 (moveit#3382)
1 parent ad9ef81 commit 5caf92c

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

‎moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@
5757
#include <moveit/utils/logger.hpp>
5858

5959
static const rclcpp::Duration CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1.0);
60-
static const double SERVICE_CALL_TIMEOUT = 1.0;
60+
// TODO: Create a ROS parameter allowing to customize this default timeout
61+
static constexpr double SERVICE_CALL_TIMEOUT = 3.0;
6162

6263
namespace moveit_ros_control_interface
6364
{

0 commit comments

Comments
 (0)