KukaLBRiiwaROSPlugin_LOCAL_26696.hpp
Go to the documentation of this file.
1 #ifndef GRL_ROS_BRIDGE_HPP_
2 #define GRL_ROS_BRIDGE_HPP_
3 
4 #include <iostream>
5 #include <memory>
6 #include <array>
7 
8 #include <boost/log/trivial.hpp>
9 #include <boost/exception/all.hpp>
10 #include <boost/algorithm/string.hpp>
11 #include <boost/thread/mutex.hpp>
12 #include <boost/thread/locks.hpp>
13 
14 #include <ros/ros.h>
15 #include <trajectory_msgs/JointTrajectory.h>
16 #include <trajectory_msgs/JointTrajectoryPoint.h>
17 #include <sensor_msgs/JointState.h>
18 #include <std_msgs/String.h>
19 #include <geometry_msgs/Wrench.h>
20 
21 #include "grl/kuka/KukaDriver.hpp"
25 
26 
27 /// @todo move elsewhere, because it will conflict with others' implementations of outputting vectors
28 template<typename T>
29 inline boost::log::formatting_ostream& operator<<(boost::log::formatting_ostream& out, std::vector<T>& v)
30 {
31  out << "[";
32  size_t last = v.size() - 1;
33  for(size_t i = 0; i < v.size(); ++i) {
34  out << v[i];
35  if (i != last)
36  out << ", ";
37  }
38  out << "]";
39  return out;
40 }
41 
42 namespace grl {
43 
44  namespace ros {
45 
46  /**
47  *
48  * This class contains code to offer a simple communication layer between ROS and the KUKA LBR iiwa
49  *
50  * @todo Main Loop Update Rate must be supplied to underlying Driver for FRI mode. see KukaLBRiiwaVrepPlugin for reference, particularly kukaDriverP_->set(simulationTimeStep_,time_duration_command_tag());
51  */
52  class KukaLBRiiwaROSPlugin : public std::enable_shared_from_this<KukaLBRiiwaROSPlugin>
53  {
54  public:
55 
56  enum ParamIndex {
57  RobotName,
58  RobotModel,
67  };
68 
69  typedef std::tuple<
70  std::string,
71  std::string,
72  std::string,
73  std::string,
74  std::string,
75  std::string,
76  std::string,
77  std::string,
78  std::string,
79  std::string
80  > Params;
81 
82 
83  static const Params defaultParams(){
84  return std::make_tuple(
85  "Robotiiwa" , // RobotName,
86  "KUKA_LBR_IIWA_14_R820" , // RobotModel (options are KUKA_LBR_IIWA_14_R820, KUKA_LBR_IIWA_7_R800)
87  "172.31.1.101" , // LocalZMQAddress // only insert ip, not the port
88  "tcp://172.31.1.147:30010", // RemoteZMQAddress
89  "192.170.10.100" , // LocalHostKukaKoniUDPAddress,
90  "30200" , // LocalHostKukaKoniUDPPort,
91  "192.170.10.2" , // RemoteHostKukaKoniUDPAddress,
92  "30200" , // RemoteHostKukaKoniUDPPort
93  "JAVA" , // KukaCommandMode (options are FRI, JAVA)
94  "FRI" // KukaMonitorMode (options are FRI, JAVA)
95  );
96  }
97 
99  ::ros::NodeHandle nh_tilde("~");
100 
101  nh_tilde.getParam("RobotName",std::get<RobotName>(params));
102  nh_tilde.getParam("RobotModel",std::get<RobotModel>(params));
103  nh_tilde.getParam("LocalZMQAddress",std::get<LocalZMQAddress>(params));
104  nh_tilde.getParam("RemoteZMQAddress",std::get<RemoteZMQAddress>(params));
105  nh_tilde.getParam("LocalHostKukaKoniUDPAddress",std::get<LocalHostKukaKoniUDPAddress>(params));
106  nh_tilde.getParam("LocalHostKukaKoniUDPPort",std::get<LocalHostKukaKoniUDPPort>(params));
107  nh_tilde.getParam("RemoteHostKukaKoniUDPAddress",std::get<RemoteHostKukaKoniUDPAddress>(params));
108  nh_tilde.getParam("RemoteHostKukaKoniUDPPort",std::get<RemoteHostKukaKoniUDPPort>(params));
109  nh_tilde.getParam("KukaCommandMode",std::get<KukaCommandMode>(params));
110  nh_tilde.getParam("KukaMonitorMode",std::get<KukaMonitorMode>(params));
111 
112  return params;
113  }
114 
115  /// unique tag type so State never
116  /// conflicts with a similar tuple
117  struct JointStateTag{};
118 
121  JointForce,
125  JointMatrix,
127  };
128 
129 
130  typedef std::vector<double> JointScalar;
131 
132  /// @see http://www.coppeliarobotics.com/helpFiles/en/apiFunctions.htm#simGetJointMatrix for data layout information
133  typedef std::array<double,12> TransformationMatrix;
134  typedef std::vector<TransformationMatrix> TransformationMatrices;
135 
136  typedef std::tuple<
137  JointScalar, // jointPosition
138  // JointScalar // JointVelocity // no velocity yet
139  JointScalar, // jointForce
140  JointScalar, // jointTargetPosition
141  JointScalar, // JointLowerPositionLimit
142  JointScalar, // JointUpperPositionLimit
143  TransformationMatrices, // jointTransformation
144  robot::arm::KukaJAVAdriver::JointStateTag // JointStateTag unique identifying type so tuple doesn't conflict
145  > State;
146 
147 
149  : debug(false),params_(params), nh_("")
150  {
151  loadRosParams(params_);
152  }
153 
154  void construct(){ construct(params_);}
155 
156  /// @todo create a function that calls simGetObjectHandle and throws an exception when it fails
157  /// @warning getting the ik group is optional, so it does not throw an exception
158  void construct(Params params) {
159 
160  current_js_.name.resize(7);
161  current_js_.name[0] = "iiwa_joint_1";
162  current_js_.name[1] = "iiwa_joint_2";
163  current_js_.name[2] = "iiwa_joint_3";
164  current_js_.name[3] = "iiwa_joint_4";
165  current_js_.name[4] = "iiwa_joint_5";
166  current_js_.name[5] = "iiwa_joint_6";
167  current_js_.name[6] = "iiwa_joint_7";
168  current_js_.velocity.resize(7);
169  current_js_.velocity[0] = 0.;
170  current_js_.velocity[1] = 0.;
171  current_js_.velocity[2] = 0.;
172  current_js_.velocity[3] = 0.;
173  current_js_.velocity[4] = 0.;
174  current_js_.velocity[5] = 0.;
175  current_js_.velocity[6] = 0.;
176 
177  ::ros::NodeHandle nh;
178  js_pub_ = nh.advertise<sensor_msgs::JointState>("joint_states",100);
179  jt_sub_ = nh.subscribe<trajectory_msgs::JointTrajectory>("joint_traj_cmd", 1000, &KukaLBRiiwaROSPlugin::jt_callback, this);
180  jt_pt_sub_ = nh.subscribe<trajectory_msgs::JointTrajectoryPoint>("joint_traj_pt_cmd", 1000, &KukaLBRiiwaROSPlugin::jt_pt_callback, this);
181  wrench_pub_ = nh.advertise<geometry_msgs::Wrench>("slave/wrench_r",100);
182  mode_sub_ = nh.subscribe<std_msgs::String>("interaction_mode", 1000, &KukaLBRiiwaROSPlugin::mode_callback, this);
183  ROS_INFO("done creating subscribers");
184  //jt_sub_ = nh.subscribe<trajectory_msgs::JointTrajectory>("joint_traj_cmd",1000,boost::bind(&KukaLBRiiwaROSPlugin::jt_callback, this, _1));
185 
186  params_ = params;
187  // keep driver threads from exiting immediately after creation, because they have work to do!
188  device_driver_workP_.reset(new boost::asio::io_service::work(device_driver_io_service));
189 
190  /// @todo properly support passing of io_service
191  KukaDriverP_.reset(
193  //device_driver_io_service,
194  params
195  // std::make_tuple(
196  // std::string(std::std::get<LocalHostKukaKoniUDPAddress > (params)),
197  // std::string(std::std::get<LocalHostKukaKoniUDPPort > (params)),
198  // std::string(std::std::get<RemoteHostKukaKoniUDPAddress> (params)),
199  // std::string(std::std::get<RemoteHostKukaKoniUDPPort > (params)),
200  // grl::robot::arm::KukaFRIClientDataDriver::run_automatically
201  // )
202  )
203 
204  );
205  KukaDriverP_->construct();
206  }
207 
208 
209 
210 
211  bool setState(State& state) { return true; }
212 
213 
214  const Params & getParams(){
215  return params_;
216  }
217 
218  /**
219  * ROS joint trajectory callback
220  * this code needs to execute the joint trajectory on the robot
221  */
222  void jt_callback(const trajectory_msgs::JointTrajectoryConstPtr &msg) {
223  boost::lock_guard<boost::mutex> lock(jt_mutex);
224 
225 
226  for(auto &pt: msg->points) {
227  // positions velocities ac
228  if (pt.positions.size() != KUKA::LBRState::NUM_DOF) {
229  BOOST_THROW_EXCEPTION(std::runtime_error("Malformed joint trajectory request! Wrong number of joints."));
230  }
231 
232  // handle
233  //simJointPosition
234  simJointPosition.clear();
235  boost::copy(pt.positions,std::back_inserter(simJointPosition));
236  //simJointVelocity
237  simJointVelocity.clear();
238  boost::copy(pt.velocities,std::back_inserter(simJointVelocity));
239  //simJointForce
240  simJointForce.clear();
241  boost::copy(pt.effort,std::back_inserter(simJointForce));
242 
243  ///@todo: execute the rest of the trajectory
244  break;
245  }
246 
247  }
248 
249 
250  /// ROS callback to set current interaction mode; determines whether commands will be send in SERVO, TEACH, etc
251  void mode_callback(const std_msgs::StringConstPtr &msg) {
252  boost::lock_guard<boost::mutex> lock(jt_mutex);
253 
254  //std::cerr << "Mode command = " << msg->data.c_str() << "\n";
255  if (debug) {
256  ROS_INFO("Receiving mode command: %s", msg->data.c_str());
257  }
258 
259  unsigned int ArmStateLen = 9;
260  for (unsigned int i = 0; i < ArmStateLen; ++i) {
261  if (msg->data == grl::flatbuffer::EnumNamesArmState()[i]) {
262 
263  if (debug) {
264  std::string info = std::string("Valid grl::flatbuffer::ArmState command received for ") + grl::flatbuffer::EnumNamesArmState()[i] + std::string(" mode");
265  ROS_INFO(info.c_str());
266  }
267 
268  interaction_mode = static_cast<grl::flatbuffer::ArmState>(i);
269  KukaDriverP_->set(interaction_mode);
270  break;
271  }
272  }
273 
274  }
275 
276  /// ROS joint trajectory callback
277  /// this code needs to execute the joint trajectory on the robot
278  void jt_pt_callback(const trajectory_msgs::JointTrajectoryPointConstPtr &msg) {
279  boost::lock_guard<boost::mutex> lock(jt_mutex);
280 
281  // positions velocities ac
282  if (msg->positions.size() != KUKA::LBRState::NUM_DOF) {
283  BOOST_THROW_EXCEPTION(std::runtime_error("Malformed joint trajectory request! Wrong number of joints."));
284  }
285 
286  // handle
287  //simJointPosition
288  simJointPosition.clear();
289  boost::copy(msg->positions,std::back_inserter(simJointPosition));
290  //simJointVelocity
291  simJointVelocity.clear();
292  boost::copy(msg->velocities,std::back_inserter(simJointVelocity));
293  //simJointForce
294  simJointForce.clear();
295  boost::copy(msg->effort,std::back_inserter(simJointForce));
296 
297  ///@todo: execute the rest of the trajectory
298  }
299 
300 
302  device_driver_workP_.reset();
303 
304  if(driver_threadP){
306  driver_threadP->join();
307  }
308  }
309 
310  ///
311  /// @brief spin once, call this repeatedly to run the driver
312  ///
313  ///
314  bool run_one()
315  {
316 
317  bool haveNewData = false;
318 
319  if(KukaDriverP_){
320 
321 
322  switch(interaction_mode) {
324  if (debug) {
325  ROS_INFO("Arm is in SERVO Mode");
326  }
328  /// @todo setting joint position clears joint force in KukaDriverP_. Is this right or should position and force be configurable simultaeously?
329  //if(simJointForce.size()) KukaDriverP_->set( simJointForce, grl::revolute_joint_torque_open_chain_command_tag());
330  break;
332  if (debug) {
333  ROS_INFO("Arm is in TEACH mode");
334  }
335  break;
336  break;
338  break;
340  break;
342  if (debug) {
343  ROS_INFO("Sending start!");
344  }
345  break;
347  break;
348  default:
349  ROS_INFO("KukaLBRiiwaROSPlugin in unsupported mode!");
350  }
351 
352  haveNewData = KukaDriverP_->run_one();
353 
354  if(haveNewData)
355  {
356 
357  // We have the real kuka state read from the device now
358  // update real joint angle data
359  current_js_.position.clear();
360  KukaDriverP_->get(std::back_inserter(current_js_.position), grl::revolute_joint_angle_open_chain_state_tag());
361 
362  current_js_.effort.clear();
363  KukaDriverP_->get(std::back_inserter(current_js_.effort), grl::revolute_joint_torque_open_chain_state_tag());
364 
365  //current_js_.velocity.clear();
366  //grl::robot::arm::copy(friData_->monitoringMsg, std::back_inserter(current_js_.velocity), grl::revolute_joint_angle_open_chain_state_tag());
367  current_js_.header.stamp = ::ros::Time::now();
368  current_js_.header.seq += 1;
369  js_pub_.publish(current_js_);
370  }
371 
372  if(haveNewData)
373  {
374  std::vector<double> wrench_vector;
375  KukaDriverP_->getWrench(std::back_inserter(wrench_vector));
376  if (!wrench_vector.empty())
377  {
378  current_wrench.force.x = wrench_vector[0];
379  current_wrench.force.y = wrench_vector[1];
380  current_wrench.force.z = wrench_vector[2];
381  current_wrench.torque.x = wrench_vector[3];
382  current_wrench.torque.y = wrench_vector[4];
383  current_wrench.torque.z = wrench_vector[5];
384  }
385  wrench_pub_.publish(current_wrench);
386  }
387 
388  }
389 
390  return haveNewData;
391  }
392 
393  boost::asio::io_service device_driver_io_service;
394  std::unique_ptr<boost::asio::io_service::work> device_driver_workP_;
395  std::unique_ptr<std::thread> driver_threadP;
396 
397  /// @todo replace all these simJoint elements with simple KukaLBRiiwaROSPlugin::State
398  std::vector<double> simJointPosition;// = {0.0,0.0,0.0,0.0,0.0,0.0,0.0};
399  std::vector<double> simJointVelocity = {0.0,0.0,0.0,0.0,0.0,0.0,0.0};
400  std::vector<double> simJointForce;// = {0.0,0.0,0.0,0.0,0.0,0.0,0.0};
401  std::vector<double> simJointTargetPosition = {0.0,0.0,0.0,0.0,0.0,0.0,0.0};
403 
404  /// @note loss of precision! kuka sends double values, if you write custom code don't use these float values. Vrep uses floats internally which is why they are used here.
405  std::vector<double> realJointPosition = { 0, 0, 0, 0, 0, 0, 0 };
406  // does not exist
407  std::vector<double> realJointForce = { 0, 0, 0, 0, 0, 0, 0 };
408 
409  private:
410 
411  bool debug;
412  grl::flatbuffer::ArmState interaction_mode;
413 
414  boost::mutex jt_mutex;
415  boost::shared_ptr<robot::arm::KukaDriver> KukaDriverP_;
416  Params params_;
417 
418  ::ros::Subscriber jt_sub_; // subscribes to joint state trajectories and executes them
419  ::ros::Subscriber jt_pt_sub_; // subscribes to joint state trajectories and executes them
420  ::ros::Subscriber mode_sub_; // subscribes to interaction mode messages (strings for now)
421 
422  ::ros::Publisher js_pub_; // publish true joint states from the KUKA
423  ::ros::Publisher wrench_pub_;
424 
425  sensor_msgs::JointState current_js_;
426  geometry_msgs::Wrench current_wrench;
427 
428  ::ros::NodeHandle nh_;
429 
430  };
431  }
432 }
433 
434 
435 #endif
void jt_pt_callback(const trajectory_msgs::JointTrajectoryPointConstPtr &msg)
bool run_one()
spin once, call this repeatedly to run the driver
std::vector< double > simJointTargetPosition
void jt_callback(const trajectory_msgs::JointTrajectoryConstPtr &msg)
OutputIterator copy(std::string model, OutputIterator it, grl::revolute_joint_velocity_open_chain_state_constraint_tag)
copy vector of joint velocity limits in radians/s
Definition: Kuka.hpp:131
boost::asio::io_service device_driver_io_service
const char ** EnumNamesArmState()
Kuka LBR iiwa Primary Multi Mode Driver, supports communication over FRI and JAVA interfaces...
Definition: KukaDriver.hpp:41
std::tuple< JointScalar, JointScalar, JointScalar, JointScalar, JointScalar, TransformationMatrices, robot::arm::KukaJAVAdriver::JointStateTag > State
const int NUM_DOF
Definition: Kuka.hpp:19
void mode_callback(const std_msgs::StringConstPtr &msg)
ROS callback to set current interaction mode; determines whether commands will be send in SERVO...
KukaLBRiiwaROSPlugin(Params params=defaultParams())
std::unique_ptr< boost::asio::io_service::work > device_driver_workP_
std::unique_ptr< std::thread > driver_threadP
std::tuple< std::string, std::string, std::string, std::string, std::string, std::string, std::string, std::string, std::string, std::string > Params
KukaLBRiiwaROSPlugin::TransformationMatrices simJointTransformationMatrix
std::vector< TransformationMatrix > TransformationMatrices