46 static const std::string
IP_ADDR_ARG(
"~robot_ip_address");
52 static const std::string
PREFIX_ARG(
"~prefix");
59 static const std::vector<std::string>
DEFAULT_JOINTS = {
"shoulder_pan_joint",
"shoulder_lift_joint",
"elbow_joint",
60 "wrist_1_joint",
"wrist_2_joint",
"wrist_3_joint" };
89 LOG_INFO(
"Starting pipeline %s", name.c_str());
93 LOG_INFO(
"Stopping pipeline %s", name.c_str());
102 LOG_INFO(
"Starting pipeline %s", name.c_str());
106 LOG_INFO(
"Shutting down on stopped pipeline %s", name.c_str());
116 LOG_ERROR(
"robot_ip_address parameter must be set!");
137 return stream.
connect() ? stream.
getIP() : std::string();
140 int main(
int argc,
char **argv)
152 [&args](std::string name) {
return args.
prefix + name; });
157 if (local_ip.empty())
163 vector<Service *> services;
171 vector<IConsumer<RTPacket> *> rt_vec{ &rt_pub };
183 rt_vec.push_back(controller);
184 services.push_back(controller);
192 LOG_INFO(
"Use low bandwidth trajectory follower");
198 LOG_INFO(
"Use standard trajectory follower");
202 rt_vec.push_back(action_server);
203 services.push_back(action_server);
207 services.push_back(&urscript_handler);
210 LOG_INFO(
"Notifier: Pipeline disconnect will shutdown the node");
215 LOG_INFO(
"Notifier: Pipeline disconnect will be ignored.");
230 vector<IConsumer<StatePacket> *> state_vec{ &state_pub, &service_stopper };
239 auto state_commander = factory.
getCommander(state_stream);
243 action_server->
start();
247 LOG_INFO(
"ROS stopping, shutting down pipelines");
255 LOG_INFO(
"Pipelines shutdown complete");
std::unique_ptr< URParser< StatePacket > > getStateParser()
bool shutdown_on_disconnect
static const std::string JOINT_NAMES_PARAM("hardware_interface/joints")
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
void started(std::string name)
static const std::string REVERSE_PORT_ARG("~reverse_port")
std::vector< std::string > joint_names
static const std::string LOW_BANDWIDTH_TRAJECTORY_FOLLOWER("~use_lowbandwidth_trajectory_follower")
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const int UR_RT_PORT
static const std::string BASE_FRAME_ARG("~base_frame")
static const std::string MAX_VEL_CHANGE_ARG("~max_vel_change")
ROSCPP_DECL void spin(Spinner &spinner)
std::string getLocalIPAccessibleFromHost(std::string &host)
static const std::string TCP_LINK_ARG("~tcp_link")
static const int UR_SECONDARY_PORT
static const std::string IP_ADDR_ARG("~robot_ip_address")
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void stopped(std::string name)
static const std::string REVERSE_IP_ADDR_ARG("~reverse_ip_address")
bool use_lowbandwidth_trajectory_follower
#define LOG_INFO(format,...)
static const std::string ROS_CONTROL_ARG("~use_ros_control")
int main(int argc, char **argv)
static const std::string PREFIX_ARG("~prefix")
std::unique_ptr< URParser< RTPacket > > getRTParser()
std::string reverse_ip_address
static const std::string SHUTDOWN_ON_DISCONNECT_ARG("~shutdown_on_disconnect")
std::unique_ptr< URCommander > getCommander(URStream &stream)
void stopped(std::string name)
static const std::vector< std::string > DEFAULT_JOINTS
bool parse_args(ProgArgs &args)
ROSCPP_DECL void shutdown()
void started(std::string name)
static const std::string TOOL_FRAME_ARG("~tool_frame")
#define LOG_ERROR(format,...)