1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Change default activation mode to 'Never'

Maintains default behavior of indigo that no controller activation is required.
Enabling required activation can be done by passing 'require_activation' as Always/OnStartup
to the ur_common.launch or by modifying corresponding launch files.
This commit is contained in:
Henning Kayser
2017-08-17 13:39:05 +02:00
parent f70255926b
commit 231840fabf
3 changed files with 14 additions and 11 deletions

View File

@@ -14,8 +14,8 @@ enum class RobotState
enum class ActivationMode enum class ActivationMode
{ {
Always,
Never, Never,
Always,
OnStartup OnStartup
}; };

View File

@@ -17,7 +17,7 @@
<arg name="tool_frame" default="$(arg prefix)tool0_controller" /> <arg name="tool_frame" default="$(arg prefix)tool0_controller" />
<!-- require_activation defines when the service /ur_driver/robot_enable needs to be called. --> <!-- require_activation defines when the service /ur_driver/robot_enable needs to be called. -->
<arg name="require_activation" default="Always" /> <!-- Always, Never, OnStartup --> <arg name="require_activation" default="Never" /> <!-- Never, Always, OnStartup -->
<!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits --> <!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits -->
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->

View File

@@ -4,26 +4,29 @@ ServiceStopper::ServiceStopper(std::vector<Service*> services)
: enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this)) : enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
, services_(services) , services_(services)
, last_state_(RobotState::Error) , last_state_(RobotState::Error)
, activation_mode_(ActivationMode::Always) , activation_mode_(ActivationMode::Never)
{ {
std::string mode; std::string mode;
ros::param::param("~require_activation", mode, std::string("Always")); ros::param::param("~require_activation", mode, std::string("Never"));
if (mode == "Never") if (mode == "Always")
{ {
activation_mode_ = ActivationMode::Never; activation_mode_ = ActivationMode::Always;
notify_all(RobotState::Running);
} }
else if (mode == "OnStartup") else if (mode == "OnStartup")
{ {
activation_mode_ = ActivationMode::OnStartup; activation_mode_ = ActivationMode::OnStartup;
} }
else if (mode != "Always") else
{ {
LOG_WARN("Found invalid value for param service_stopper_mode: '%s'\nShould be one of Always, Never, OnStartup", mode.c_str()); if (mode != "Never")
mode = "Always"; {
LOG_WARN("Found invalid value for param require_activation: '%s'\nShould be one of Never, OnStartup, Always", mode.c_str());
mode = "Never";
}
notify_all(RobotState::Running);
} }
LOG_INFO("ActivationMode mode: %s", mode.c_str()); LOG_INFO("Service 'ur_driver/robot_enable' activation mode: %s", mode.c_str());
} }
bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp) bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp)