ros_main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017, 2018 Jarek Potiuk (low bandwidth trajectory follower)
3  *
4  * Copyright 2017, 2018 Simon Rasmussen (refactor)
5  *
6  * Copyright 2015, 2016 Thomas Timm Andersen (original version)
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13  *
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 #include <ros/ros.h>
22 #include <chrono>
23 #include <cstdlib>
24 #include <string>
25 #include <thread>
26 
27 #include "ur_modern_driver/log.h"
45 
46 static const std::string IP_ADDR_ARG("~robot_ip_address");
47 static const std::string REVERSE_IP_ADDR_ARG("~reverse_ip_address");
48 static const std::string REVERSE_PORT_ARG("~reverse_port");
49 static const std::string ROS_CONTROL_ARG("~use_ros_control");
50 static const std::string LOW_BANDWIDTH_TRAJECTORY_FOLLOWER("~use_lowbandwidth_trajectory_follower");
51 static const std::string MAX_VEL_CHANGE_ARG("~max_vel_change");
52 static const std::string PREFIX_ARG("~prefix");
53 static const std::string BASE_FRAME_ARG("~base_frame");
54 static const std::string TOOL_FRAME_ARG("~tool_frame");
55 static const std::string TCP_LINK_ARG("~tcp_link");
56 static const std::string JOINT_NAMES_PARAM("hardware_interface/joints");
57 static const std::string SHUTDOWN_ON_DISCONNECT_ARG("~shutdown_on_disconnect");
58 
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" };
61 
62 static const int UR_SECONDARY_PORT = 30002;
63 static const int UR_RT_PORT = 30003;
64 
65 struct ProgArgs
66 {
67 public:
68  std::string host;
69  std::string prefix;
70  std::string base_frame;
71  std::string tool_frame;
72  std::string tcp_link;
73  std::string reverse_ip_address;
74  int32_t reverse_port;
75  std::vector<std::string> joint_names;
77  double max_velocity;
82 };
83 
85 {
86 public:
87  void started(std::string name)
88  {
89  LOG_INFO("Starting pipeline %s", name.c_str());
90  }
91  void stopped(std::string name)
92  {
93  LOG_INFO("Stopping pipeline %s", name.c_str());
94  }
95 };
96 
98 {
99 public:
100  void started(std::string name)
101  {
102  LOG_INFO("Starting pipeline %s", name.c_str());
103  }
104  void stopped(std::string name)
105  {
106  LOG_INFO("Shutting down on stopped pipeline %s", name.c_str());
107  ros::shutdown();
108  exit(1);
109  }
110 };
111 
113 {
114  if (!ros::param::get(IP_ADDR_ARG, args.host))
115  {
116  LOG_ERROR("robot_ip_address parameter must be set!");
117  return false;
118  }
120  ros::param::param(REVERSE_PORT_ARG, args.reverse_port, int32_t(50001));
125  ros::param::param(PREFIX_ARG, args.prefix, std::string());
126  ros::param::param(BASE_FRAME_ARG, args.base_frame, args.prefix + "base_link");
127  ros::param::param(TOOL_FRAME_ARG, args.tool_frame, args.prefix + "tool0_controller");
128  ros::param::param(TCP_LINK_ARG, args.tcp_link, args.prefix + "tool0");
131  return true;
132 }
133 
134 std::string getLocalIPAccessibleFromHost(std::string &host)
135 {
136  URStream stream(host, UR_RT_PORT);
137  return stream.connect() ? stream.getIP() : std::string();
138 }
139 
140 int main(int argc, char **argv)
141 {
142  ros::init(argc, argv, "ur_driver");
143 
144  ProgArgs args;
145  if (!parse_args(args))
146  {
147  return EXIT_FAILURE;
148  }
149 
150  // Add prefix to joint names
151  std::transform(args.joint_names.begin(), args.joint_names.end(), args.joint_names.begin(),
152  [&args](std::string name) { return args.prefix + name; });
153 
154  std::string local_ip(args.reverse_ip_address);
155 
156  // if no reverse IP address has been configured, try to detect one
157  if (local_ip.empty())
158  {
159  local_ip = getLocalIPAccessibleFromHost(args.host);
160  }
161 
162  URFactory factory(args.host);
163  vector<Service *> services;
164 
165  // RT packets
166  auto rt_parser = factory.getRTParser();
167  URStream rt_stream(args.host, UR_RT_PORT);
168  URProducer<RTPacket> rt_prod(rt_stream, *rt_parser);
169  RTPublisher rt_pub(args.prefix, args.base_frame, args.tool_frame, args.use_ros_control);
170  auto rt_commander = factory.getCommander(rt_stream);
171  vector<IConsumer<RTPacket> *> rt_vec{ &rt_pub };
172 
173  INotifier *notifier(nullptr);
174  ROSController *controller(nullptr);
175  ActionServer *action_server(nullptr);
176  if (args.use_ros_control)
177  {
178  LOG_INFO("ROS control enabled");
179  TrajectoryFollower *traj_follower =
180  new TrajectoryFollower(*rt_commander, local_ip, args.reverse_port, factory.isVersion3());
181  controller =
182  new ROSController(*rt_commander, *traj_follower, args.joint_names, args.max_vel_change, args.base_frame);
183  rt_vec.push_back(controller);
184  services.push_back(controller);
185  }
186  else
187  {
188  LOG_INFO("ActionServer enabled");
189  ActionTrajectoryFollowerInterface *traj_follower(nullptr);
191  {
192  LOG_INFO("Use low bandwidth trajectory follower");
193  traj_follower =
194  new LowBandwidthTrajectoryFollower(*rt_commander, local_ip, args.reverse_port, factory.isVersion3());
195  }
196  else
197  {
198  LOG_INFO("Use standard trajectory follower");
199  traj_follower = new TrajectoryFollower(*rt_commander, local_ip, args.reverse_port, factory.isVersion3());
200  }
201  action_server = new ActionServer(*traj_follower, args.joint_names, args.max_velocity);
202  rt_vec.push_back(action_server);
203  services.push_back(action_server);
204  }
205 
206  URScriptHandler urscript_handler(*rt_commander);
207  services.push_back(&urscript_handler);
208  if (args.shutdown_on_disconnect)
209  {
210  LOG_INFO("Notifier: Pipeline disconnect will shutdown the node");
211  notifier = new ShutdownOnPipelineStoppedNotifier();
212  }
213  else
214  {
215  LOG_INFO("Notifier: Pipeline disconnect will be ignored.");
216  notifier = new IgnorePipelineStoppedNotifier();
217  }
218 
219  MultiConsumer<RTPacket> rt_cons(rt_vec);
220  Pipeline<RTPacket> rt_pl(rt_prod, rt_cons, "RTPacket", *notifier);
221 
222  // Message packets
223  auto state_parser = factory.getStateParser();
224  URStream state_stream(args.host, UR_SECONDARY_PORT);
225  URProducer<StatePacket> state_prod(state_stream, *state_parser);
226  MBPublisher state_pub;
227 
228  ServiceStopper service_stopper(services);
229 
230  vector<IConsumer<StatePacket> *> state_vec{ &state_pub, &service_stopper };
231  MultiConsumer<StatePacket> state_cons(state_vec);
232  Pipeline<StatePacket> state_pl(state_prod, state_cons, "StatePacket", *notifier);
233 
234  LOG_INFO("Starting main loop");
235 
236  rt_pl.run();
237  state_pl.run();
238 
239  auto state_commander = factory.getCommander(state_stream);
240  IOService io_service(*state_commander);
241 
242  if (action_server)
243  action_server->start();
244 
245  ros::spin();
246 
247  LOG_INFO("ROS stopping, shutting down pipelines");
248 
249  rt_pl.stop();
250  state_pl.stop();
251 
252  if (controller)
253  delete controller;
254 
255  LOG_INFO("Pipelines shutdown complete");
256 
257  return EXIT_SUCCESS;
258 }
bool connect()
Definition: stream.h:47
std::unique_ptr< URParser< StatePacket > > getStateParser()
Definition: factory.h:107
bool shutdown_on_disconnect
Definition: ros_main.cpp:81
static const std::string JOINT_NAMES_PARAM("hardware_interface/joints")
bool param(const std::string &param_name, T &param_val, const T &default_val)
void started(std::string name)
Definition: ros_main.cpp:100
double max_vel_change
Definition: ros_main.cpp:78
void run()
Definition: pipeline.h:205
static const std::string REVERSE_PORT_ARG("~reverse_port")
std::string tool_frame
Definition: ros_main.cpp:71
std::vector< std::string > joint_names
Definition: ros_main.cpp:75
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
Definition: ros_main.cpp:63
static const std::string BASE_FRAME_ARG("~base_frame")
static const std::string MAX_VEL_CHANGE_ARG("~max_vel_change")
bool use_ros_control
Definition: ros_main.cpp:79
ROSCPP_DECL void spin(Spinner &spinner)
std::string getLocalIPAccessibleFromHost(std::string &host)
Definition: ros_main.cpp:134
static const std::string TCP_LINK_ARG("~tcp_link")
static const int UR_SECONDARY_PORT
Definition: ros_main.cpp:62
void stop()
Definition: pipeline.h:216
bool isVersion3()
Definition: factory.h:92
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)
Definition: ros_main.cpp:104
static const std::string REVERSE_IP_ADDR_ARG("~reverse_ip_address")
bool use_lowbandwidth_trajectory_follower
Definition: ros_main.cpp:80
#define LOG_INFO(format,...)
Definition: log.h:35
std::string tcp_link
Definition: ros_main.cpp:72
static const std::string ROS_CONTROL_ARG("~use_ros_control")
int main(int argc, char **argv)
Definition: ros_main.cpp:140
static const std::string PREFIX_ARG("~prefix")
std::unique_ptr< URParser< RTPacket > > getRTParser()
Definition: factory.h:124
std::string reverse_ip_address
Definition: ros_main.cpp:73
static const std::string SHUTDOWN_ON_DISCONNECT_ARG("~shutdown_on_disconnect")
std::unique_ptr< URCommander > getCommander(URStream &stream)
Definition: factory.h:97
void stopped(std::string name)
Definition: ros_main.cpp:91
static const std::vector< std::string > DEFAULT_JOINTS
Definition: ros_main.cpp:59
bool parse_args(ProgArgs &args)
Definition: ros_main.cpp:112
std::string getIP()
Definition: tcp_socket.cpp:117
std::string base_frame
Definition: ros_main.cpp:70
double max_acceleration
Definition: ros_main.cpp:76
ROSCPP_DECL void shutdown()
void started(std::string name)
Definition: ros_main.cpp:87
double max_velocity
Definition: ros_main.cpp:77
std::string prefix
Definition: ros_main.cpp:69
int32_t reverse_port
Definition: ros_main.cpp:74
static const std::string TOOL_FRAME_ARG("~tool_frame")
#define LOG_ERROR(format,...)
Definition: log.h:36
std::string host
Definition: ros_main.cpp:68


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