37 ROS_ERROR(
"IndustrialRobotStatusController: Could not get Industrial "
38 "Robot Status interface from hardware");
49 std::string handle_name =
"industrial_robot_status_handle";
50 if (!controller_node_handle.
getParam(
"handle_name", handle_name))
53 "parameter. Using default '" << handle_name <<
"'.");
64 "robot status handle: " << ex.
what());
84 return industrial_msgs::TriState::TRUE;
86 return industrial_msgs::TriState::FALSE;
88 return industrial_msgs::TriState::UNKNOWN;
95 return industrial_msgs::RobotMode::MANUAL;
97 return industrial_msgs::RobotMode::AUTO;
99 return industrial_msgs::RobotMode::UNKNOWN;