24 LOG_INFO(
"Initializing ur_driver/URScript subscriber");
26 LOG_INFO(
"The ur_driver/URScript initialized");
32 std::string str(msg->data);
33 if (str.back() !=
'\n')
51 LOG_ERROR(
"Robot is not ready, check robot_mode");
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)
#define LOG_INFO(format,...)
ros::Subscriber urscript_sub_
URScriptHandler(URCommander &commander)
void urscriptInterface(const std_msgs::String::ConstPtr &msg)
void onRobotStateChange(RobotState state)
#define LOG_ERROR(format,...)