urscript_handler.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017, 2018 Simon Rasmussen (refactor)
3  *
4  * Copyright 2015, 2016 Thomas Timm Andersen (original version)
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
20 #include "ur_modern_driver/log.h"
21 
22 URScriptHandler::URScriptHandler(URCommander& commander) : commander_(commander), state_(RobotState::Error)
23 {
24  LOG_INFO("Initializing ur_driver/URScript subscriber");
25  urscript_sub_ = nh_.subscribe("ur_driver/URScript", 1, &URScriptHandler::urscriptInterface, this);
26  LOG_INFO("The ur_driver/URScript initialized");
27 }
28 
29 void URScriptHandler::urscriptInterface(const std_msgs::String::ConstPtr& msg)
30 {
31  LOG_INFO("Message received");
32  std::string str(msg->data);
33  if (str.back() != '\n')
34  str.append("\n");
35 
36  switch (state_)
37  {
39  if (!commander_.uploadProg(str))
40  {
41  LOG_ERROR("Program upload failed!");
42  }
43  break;
45  LOG_ERROR("Robot is emergency stopped");
46  break;
48  LOG_ERROR("Robot is protective stopped");
49  break;
50  case RobotState::Error:
51  LOG_ERROR("Robot is not ready, check robot_mode");
52  break;
53  default:
54  LOG_ERROR("Robot is in undefined state");
55  break;
56  }
57 }
58 
60 {
61  state_ = state;
62 }
Error
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool uploadProg(const std::string &s)
Definition: commander.cpp:41
URCommander & commander_
ros::NodeHandle nh_
#define LOG_INFO(format,...)
Definition: log.h:35
ros::Subscriber urscript_sub_
URScriptHandler(URCommander &commander)
RobotState
void urscriptInterface(const std_msgs::String::ConstPtr &msg)
void onRobotStateChange(RobotState state)
#define LOG_ERROR(format,...)
Definition: log.h:36


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:01