ypspur_ros.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015-2017, the ypspur_ros authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
32 #include <diagnostic_msgs/DiagnosticArray.h>
33 #include <geometry_msgs/Twist.h>
34 #include <geometry_msgs/WrenchStamped.h>
35 #include <nav_msgs/Odometry.h>
36 #include <sensor_msgs/JointState.h>
37 #include <std_msgs/Bool.h>
38 #include <std_msgs/Float32.h>
39 #include <std_msgs/Float32MultiArray.h>
40 #include <trajectory_msgs/JointTrajectory.h>
41 #include <ypspur_ros/ControlMode.h>
42 #include <ypspur_ros/DigitalInput.h>
43 #include <ypspur_ros/DigitalOutput.h>
44 #include <ypspur_ros/JointPositionControl.h>
45 
47 #include <tf/transform_listener.h>
48 
49 #include <signal.h>
50 #include <string.h>
51 #include <sys/ipc.h>
52 #include <sys/msg.h>
53 #include <sys/types.h>
54 #include <sys/wait.h>
55 
56 #include <boost/atomic.hpp>
57 #include <boost/chrono.hpp>
58 #include <boost/thread.hpp>
59 #include <boost/thread/future.hpp>
60 
61 #include <exception>
62 #include <map>
63 #include <string>
64 #include <vector>
65 
66 #include <compatibility.h>
67 
68 namespace YP
69 {
70 #include <ypspur.h>
71 } // namespace YP
72 
73 bool g_shutdown = false;
74 void sigintHandler(int sig)
75 {
76  g_shutdown = true;
77 }
78 
80 {
81 private:
84  std::map<std::string, ros::Publisher> pubs_;
85  std::map<std::string, ros::Subscriber> subs_;
88 
89  std::string port_;
90  std::string param_file_;
91  std::string ypspur_bin_;
92  std::map<std::string, std::string> frames_;
93  std::map<std::string, double> params_;
94  int key_;
95  bool simulate_;
97 
99 
100  pid_t pid_;
101 
103  {
105  NONE
106  };
109  {
110  public:
111  int id_;
112  std::string name_;
113  double accel_;
114  double vel_;
115  double angle_ref_;
116  double vel_ref_;
117  double vel_end_;
119  {
123  TRAJECTORY
124  };
126  trajectory_msgs::JointTrajectory cmd_joint_;
127  };
128  std::vector<JointParams> joints_;
129  std::map<std::string, int> joint_name_to_num_;
130 
131  class AdParams
132  {
133  public:
134  bool enable_;
135  std::string name_;
136  double gain_;
137  double offset_;
138  };
139  class DioParams
140  {
141  public:
142  bool enable_;
143  std::string name_;
144  bool input_;
145  bool output_;
146  };
148  std::vector<AdParams> ads_;
149  std::vector<DioParams> dios_;
150  const int ad_num_ = 8;
151  unsigned int dio_output_;
152  unsigned int dio_dir_;
153  unsigned int dio_output_default_;
154  unsigned int dio_dir_default_;
155  const int dio_num_ = 8;
156  std::map<int, ros::Time> dio_revert_;
157 
161 
162  geometry_msgs::Twist::ConstPtr cmd_vel_;
165 
167 
168  void cbControlMode(const ypspur_ros::ControlMode::ConstPtr &msg)
169  {
170  control_mode_ = msg->vehicle_control_mode;
171  switch (control_mode_)
172  {
173  case ypspur_ros::ControlMode::OPEN:
174  YP::YP_openfree();
175  break;
176  case ypspur_ros::ControlMode::TORQUE:
177  YP::YPSpur_free();
178  break;
179  case ypspur_ros::ControlMode::VELOCITY:
180  break;
181  }
182  }
183  void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
184  {
185  cmd_vel_ = msg;
186  cmd_vel_time_ = ros::Time::now();
187  if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
188  {
189  YP::YPSpur_vel(msg->linear.x, msg->angular.z);
190  }
191  }
192  void cbJoint(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
193  {
194 #if !(YPSPUR_JOINT_ANG_VEL_SUPPORT)
195  ROS_ERROR("JointTrajectory command is not available on this YP-Spur version");
196 #endif
197  const ros::Time now = ros::Time::now();
198 
199  std_msgs::Header header = msg->header;
200  if (header.stamp == ros::Time(0))
201  header.stamp = now;
202 
203  std::map<std::string, trajectory_msgs::JointTrajectory> new_cmd_joints;
204  size_t i = 0;
205  for (const std::string &name : msg->joint_names)
206  {
207  trajectory_msgs::JointTrajectory cmd_joint;
208  cmd_joint.header = header;
209  cmd_joint.joint_names.resize(1);
210  cmd_joint.joint_names[0] = name;
211  cmd_joint.points.clear();
212  std::string err_msg;
213  for (auto &cmd : msg->points)
214  {
215  if (header.stamp + cmd.time_from_start < now)
216  {
217  ROS_ERROR(
218  "Ignored outdated JointTrajectory command "
219  "(joint: %s, now: %0.6lf, stamp: %0.6lf, time_from_start: %0.6lf)",
220  name.c_str(), now.toSec(), header.stamp.toSec(), cmd.time_from_start.toSec());
221  break;
222  }
223 
224  trajectory_msgs::JointTrajectoryPoint p;
225  p.time_from_start = cmd.time_from_start;
226  p.positions.resize(1);
227  p.velocities.resize(1);
228  if (cmd.velocities.size() <= i)
229  p.velocities[0] = 0.0;
230  else
231  p.velocities[0] = cmd.velocities[i];
232  p.positions[0] = cmd.positions[i];
233 
234  cmd_joint.points.push_back(p);
235  }
236  i++;
237 
238  if (cmd_joint.points.size() != msg->points.size())
239  return;
240 
241  new_cmd_joints[name] = cmd_joint;
242  }
243  // Apply if all JointTrajectoryPoints are valid
244  for (auto &new_cmd_joint : new_cmd_joints)
245  {
246  const int joint_num = joint_name_to_num_[new_cmd_joint.first];
247  joints_[joint_num].control_ = JointParams::TRAJECTORY;
248  joints_[joint_num].cmd_joint_ = new_cmd_joint.second;
249  }
250  }
251  void cbSetVel(const std_msgs::Float32::ConstPtr &msg, int num)
252  {
253  // printf("set_vel %d %d %f\n", num, joints_[num].id_, msg->data);
254  joints_[num].vel_ = msg->data;
255 #if !(YPSPUR_JOINT_SUPPORT)
256  YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
257 #else
258  YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
259 #endif
260  }
261  void cbSetAccel(const std_msgs::Float32::ConstPtr &msg, int num)
262  {
263  // printf("set_accel %d %d %f\n", num, joints_[num].id_, msg->data);
264  joints_[num].accel_ = msg->data;
265 #if !(YPSPUR_JOINT_SUPPORT)
266  YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
267 #else
268  YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
269 #endif
270  }
271  void cbVel(const std_msgs::Float32::ConstPtr &msg, int num)
272  {
273  // printf("vel_ %d %d %f\n", num, joints_[num].id_, msg->data);
274  joints_[num].vel_ref_ = msg->data;
275  joints_[num].control_ = JointParams::VELOCITY;
276 #if !(YPSPUR_JOINT_SUPPORT)
277  YP::YP_wheel_vel(joints_[0].vel_ref_, joints_[1].vel_ref_);
278 #else
279  YP::YP_joint_vel(joints_[num].id_, joints_[num].vel_ref_);
280 #endif
281  }
282  void cbAngle(const std_msgs::Float32::ConstPtr &msg, int num)
283  {
284  joints_[num].angle_ref_ = msg->data;
285  joints_[num].control_ = JointParams::POSITION;
286 #if !(YPSPUR_JOINT_SUPPORT)
287  YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
288 #else
289  YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
290 #endif
291  }
292  void cbJointPosition(const ypspur_ros::JointPositionControl::ConstPtr &msg)
293  {
294  int i = 0;
295  for (auto &name : msg->joint_names)
296  {
297  if (joint_name_to_num_.find(name) == joint_name_to_num_.end())
298  {
299  ROS_ERROR("Unknown joint name '%s'", name.c_str());
300  continue;
301  }
302  int num = joint_name_to_num_[name];
303  // printf("%s %d %d %f", name.c_str(), num, joints_[num].id_, msg->positions[i]);
304  joints_[num].vel_ = msg->velocities[i];
305  joints_[num].accel_ = msg->accelerations[i];
306  joints_[num].angle_ref_ = msg->positions[i];
307  joints_[num].control_ = JointParams::POSITION;
308 
309 #if (YPSPUR_JOINT_SUPPORT)
310  YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
311  YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
312  YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
313 #endif
314  i++;
315  }
316 #if !(YPSPUR_JOINT_SUPPORT)
317  YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
318  YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
319  YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
320 #endif
321  }
322 
323  void cbDigitalOutput(const ypspur_ros::DigitalOutput::ConstPtr &msg, int id_)
324  {
325  const auto dio_output_prev = dio_output_;
326  const auto dio_dir_prev = dio_dir_;
327  const unsigned int mask = 1 << id_;
328 
329  switch (msg->output)
330  {
331  case ypspur_ros::DigitalOutput::HIGH_IMPEDANCE:
332  dio_output_ &= ~mask;
333  dio_dir_ &= ~mask;
334  break;
335  case ypspur_ros::DigitalOutput::LOW:
336  dio_output_ &= ~mask;
337  dio_dir_ |= mask;
338  break;
339  case ypspur_ros::DigitalOutput::HIGH:
340  dio_output_ |= mask;
341  dio_dir_ |= mask;
342  break;
343  case ypspur_ros::DigitalOutput::PULL_UP:
344  dio_output_ |= mask;
345  dio_dir_ &= ~mask;
346  break;
347  case ypspur_ros::DigitalOutput::PULL_DOWN:
348  ROS_ERROR("Digital IO pull down is not supported on this system");
349  break;
350  }
351  if (dio_output_ != dio_output_prev)
352  YP::YP_set_io_data(dio_output_);
353  if (dio_dir_ != dio_dir_prev)
354  YP::YP_set_io_dir(dio_dir_);
355 
356  if (msg->toggle_time > ros::Duration(0))
357  {
358  dio_revert_[id_] = ros::Time::now() + msg->toggle_time;
359  }
360  }
361  void revertDigitalOutput(int id_)
362  {
363  const auto dio_output_prev = dio_output_;
364  const auto dio_dir_prev = dio_dir_;
365  const unsigned int mask = 1 << id_;
366 
367  dio_output_ &= ~mask;
368  dio_output_ |= dio_output_default_ & mask;
369  dio_dir_ &= ~mask;
370  dio_dir_ |= dio_output_default_ & mask;
371 
372  if (dio_output_ != dio_output_prev)
373  YP::YP_set_io_data(dio_output_);
374  if (dio_dir_ != dio_dir_prev)
375  YP::YP_set_io_dir(dio_dir_);
376 
377  dio_revert_[id_] = ros::Time(0);
378  }
379  void updateDiagnostics(const ros::Time &now, const bool connection_down = false)
380  {
381  const int connection_error = connection_down ? 1 : YP::YP_get_error_state();
382  double t = 0;
383 
384 #if (YPSPUR_GET_DEVICE_ERROR_STATE_SUPPORT)
385  int err = 0;
386  if (!connection_error)
387  t = YP::YP_get_device_error_state(0, &err);
388  device_error_state_ |= err;
389 #else
391  "This version of yp-spur doesn't provide device error status. "
392  "Consider building ypspur_ros with latest yp-spur.");
393 #endif
394  if (device_error_state_time_ + ros::Duration(1.0) < now || connection_down ||
395  device_error_state_ != device_error_state_prev_)
396  {
397  device_error_state_time_ = now;
398  device_error_state_prev_ = device_error_state_;
399 
400  diagnostic_msgs::DiagnosticArray msg;
401  msg.header.stamp = now;
402  msg.status.resize(1);
403  msg.status[0].name = "YP-Spur Motor Controller";
404  msg.status[0].hardware_id = "ipc-key" + std::to_string(key_);
405  if (device_error_state_ == 0 && connection_error == 0)
406  {
407  if (t == 0)
408  {
409  msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
410  msg.status[0].message = "Motor controller doesn't "
411  "provide device error state.";
412  }
413  else
414  {
415  if (ros::Time(t) < now - ros::Duration(1.0))
416  {
417  msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
418  msg.status[0].message = "Motor controller doesn't "
419  "update latest device error state.";
420  }
421  else
422  {
423  msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
424  msg.status[0].message = "Motor controller is running without error.";
425  }
426  }
427  }
428  else
429  {
430  msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
431  if (connection_error)
432  msg.status[0].message +=
433  "Connection to ypspur-coordinator is down.";
434  if (device_error_state_)
435  msg.status[0].message +=
436  std::string((msg.status[0].message.size() > 0 ? " " : "")) +
437  "Motor controller reported error id " +
438  std::to_string(device_error_state_) + ".";
439  }
440  msg.status[0].values.resize(2);
441  msg.status[0].values[0].key = "connection_error";
442  msg.status[0].values[0].value = std::to_string(connection_error);
443  msg.status[0].values[1].key = "device_error";
444  msg.status[0].values[1].value = std::to_string(device_error_state_);
445 
446  pubs_["diag"].publish(msg);
447  device_error_state_ = 0;
448  }
449  }
450 
451 public:
453  : nh_()
454  , pnh_("~")
455  , device_error_state_(0)
456  , device_error_state_prev_(0)
457  , device_error_state_time_(0)
458  {
460 
461  pnh_.param("port", port_, std::string("/dev/ttyACM0"));
462  pnh_.param("ipc_key", key_, 28741);
463  pnh_.param("simulate", simulate_, false);
464  pnh_.param("simulate_control", simulate_control_, false);
465  if (simulate_control_)
466  simulate_ = true;
467  pnh_.param("ypspur_bin", ypspur_bin_, std::string("ypspur-coordinator"));
468  pnh_.param("param_file", param_file_, std::string(""));
469  pnh_.param("tf_time_offset", tf_time_offset_, 0.0);
470 
471  double cmd_vel_expire_s;
472  pnh_.param("cmd_vel_expire", cmd_vel_expire_s, -1.0);
473  cmd_vel_expire_ = ros::Duration(cmd_vel_expire_s);
474 
475  std::string ad_mask("");
476  ads_.resize(ad_num_);
477  for (int i = 0; i < ad_num_; i++)
478  {
479  pnh_.param(std::string("ad") + std::to_string(i) + std::string("_enable"),
480  ads_[i].enable_, false);
481  pnh_.param(std::string("ad") + std::to_string(i) + std::string("_name"),
482  ads_[i].name_, std::string("ad") + std::to_string(i));
483  pnh_.param(std::string("ad") + std::to_string(i) + std::string("_gain"),
484  ads_[i].gain_, 1.0);
485  pnh_.param(std::string("ad") + std::to_string(i) + std::string("_offset"),
486  ads_[i].offset_, 0.0);
487  ad_mask = (ads_[i].enable_ ? std::string("1") : std::string("0")) + ad_mask;
488  pubs_["ad/" + ads_[i].name_] = compat::advertise<std_msgs::Float32>(
489  nh_, "ad/" + ads_[i].name_,
490  pnh_, "ad/" + ads_[i].name_, 1);
491  }
492  digital_input_enable_ = false;
493  dio_output_default_ = 0;
494  dio_dir_default_ = 0;
495  dios_.resize(dio_num_);
496  for (int i = 0; i < dio_num_; i++)
497  {
499  pnh_.param(std::string("dio") + std::to_string(i) + std::string("_enable"),
500  param.enable_, false);
501  if (param.enable_)
502  {
503  pnh_.param(std::string("dio") + std::to_string(i) + std::string("_name"),
504  param.name_, std::string(std::string("dio") + std::to_string(i)));
505 
506  pnh_.param(std::string("dio") + std::to_string(i) + std::string("_output"),
507  param.output_, true);
508  pnh_.param(std::string("dio") + std::to_string(i) + std::string("_input"),
509  param.input_, false);
510 
511  if (param.output_)
512  {
513  subs_[param.name_] = compat::subscribe<ypspur_ros::DigitalOutput>(
514  nh_, param.name_,
515  pnh_, param.name_, 1,
516  boost::bind(&YpspurRosNode::cbDigitalOutput, this, _1, i));
517  }
518 
519  std::string output_default;
520  pnh_.param(std::string("dio") + std::to_string(i) + std::string("_default"),
521  output_default, std::string("HIGH_IMPEDANCE"));
522  if (output_default.compare("HIGH_IMPEDANCE") == 0)
523  {
524  }
525  else if (output_default.compare("LOW") == 0)
526  {
527  dio_dir_default_ |= 1 << i;
528  }
529  else if (output_default.compare("HIGH") == 0)
530  {
531  dio_dir_default_ |= 1 << i;
532  dio_output_default_ |= 1 << i;
533  }
534  else if (output_default.compare("PULL_UP") == 0)
535  {
536  dio_output_default_ |= 1 << i;
537  }
538  else if (output_default.compare("PULL_DOWN") == 0)
539  {
540  ROS_ERROR("Digital IO pull down is not supported on this system");
541  }
542  if (param.input_)
543  digital_input_enable_ = true;
544  }
545  dios_[i] = param;
546  }
547  dio_output_ = dio_output_default_;
548  dio_dir_ = dio_dir_default_;
549  if (digital_input_enable_)
550  {
551  pubs_["din"] = compat::advertise<ypspur_ros::DigitalInput>(
552  nh_, "digital_input",
553  pnh_, "digital_input", 2);
554  }
555 
556  pnh_.param("odom_id", frames_["odom"], std::string("odom"));
557  pnh_.param("base_link_id", frames_["base_link"], std::string("base_link"));
558  pnh_.param("origin_id", frames_["origin"], std::string(""));
559  pnh_.param("hz", params_["hz"], 200.0);
560 
561  std::string mode_name;
562  pnh_.param("OdometryMode", mode_name, std::string("diff"));
563  if (mode_name.compare("diff") == 0)
564  {
565  mode_ = DIFF;
566  pubs_["wrench"] = compat::advertise<geometry_msgs::WrenchStamped>(
567  nh_, "wrench",
568  pnh_, "wrench", 1);
569  pubs_["odom"] = compat::advertise<nav_msgs::Odometry>(
570  nh_, "odom",
571  pnh_, "odom", 1);
572  subs_["cmd_vel"] = compat::subscribe(
573  nh_, "cmd_vel",
574  pnh_, "cmd_vel", 1, &YpspurRosNode::cbCmdVel, this);
575  }
576  else if (mode_name.compare("none") == 0)
577  {
578  }
579  else
580  {
581  throw(std::runtime_error("unknown mode: " + mode_name));
582  }
583 
584  int max_joint_id;
585  bool separated_joint;
586  pnh_.param("max_joint_id", max_joint_id, 32);
587  pnh_.param("separated_joint_control", separated_joint, false);
588  int num = 0;
589  for (int i = 0; i < max_joint_id; i++)
590  {
591  std::string name;
592  name = std::string("joint") + std::to_string(i);
593  if (pnh_.hasParam(name + std::string("_enable")))
594  {
595  bool en;
596  pnh_.param(name + std::string("_enable"), en, false);
597  if (en)
598  {
599  JointParams jp;
600  jp.id_ = i;
601  pnh_.param(name + std::string("_name"), jp.name_, name);
602  pnh_.param(name + std::string("_accel"), jp.accel_, 3.14);
603  joint_name_to_num_[jp.name_] = num;
604  joints_.push_back(jp);
605  // printf("%s %d %d", jp.name_.c_str(), jp.id_, joint_name_to_num_[jp.name_]);
606  if (separated_joint)
607  {
608  subs_[jp.name_ + std::string("_setVel")] = compat::subscribe<std_msgs::Float32>(
609  nh_, jp.name_ + std::string("/set_vel"),
610  pnh_, jp.name_ + std::string("_setVel"), 1,
611  boost::bind(&YpspurRosNode::cbSetVel, this, _1, num));
612  subs_[jp.name_ + std::string("_setAccel")] = compat::subscribe<std_msgs::Float32>(
613  nh_, jp.name_ + std::string("/set_accel"),
614  pnh_, jp.name_ + std::string("_setAccel"), 1,
615  boost::bind(&YpspurRosNode::cbSetAccel, this, _1, num));
616  subs_[jp.name_ + std::string("_vel")] = compat::subscribe<std_msgs::Float32>(
617  nh_, jp.name_ + std::string("/vel"),
618  pnh_, jp.name_ + std::string("_vel"), 1,
619  boost::bind(&YpspurRosNode::cbVel, this, _1, num));
620  subs_[jp.name_ + std::string("_pos")] = compat::subscribe<std_msgs::Float32>(
621  nh_, jp.name_ + std::string("/pos"),
622  pnh_, jp.name_ + std::string("_pos"), 1,
623  boost::bind(&YpspurRosNode::cbAngle, this, _1, num));
624  }
625  subs_[std::string("joint_position")] = compat::subscribe(
626  nh_, std::string("joint_position"),
627  pnh_, std::string("joint_position"), 1, &YpspurRosNode::cbJointPosition, this);
628  num++;
629  }
630  }
631  }
632 #if !(YPSPUR_JOINT_SUPPORT)
633  if (joints_.size() != 0)
634  {
635  if (!(joints_.size() == 2 && joints_[0].id_ == 0 && joints_[1].id_ == 1))
636  {
637  throw(std::runtime_error("This version of yp-spur only supports [joint0_enable: true, joint1_enable: true]"));
638  }
639  }
640 #endif
641  if (joints_.size() > 0)
642  {
643  pubs_["joint"] = compat::advertise<sensor_msgs::JointState>(
644  nh_, "joint_states",
645  pnh_, "joint", 2);
646  subs_["joint"] = compat::subscribe(
647  nh_, "joint_trajectory",
648  pnh_, "cmd_joint", joints_.size() * 2, &YpspurRosNode::cbJoint, this);
649  }
650  subs_["control_mode"] = compat::subscribe(
651  nh_, "control_mode",
652  pnh_, "control_mode", 1, &YpspurRosNode::cbControlMode, this);
653  control_mode_ = ypspur_ros::ControlMode::VELOCITY;
654 
655  pubs_["diag"] = nh_.advertise<diagnostic_msgs::DiagnosticArray>(
656  "/diagnostics", 1);
657 
658  pid_ = 0;
659  for (int i = 0; i < 2; i++)
660  {
661  if (i > 0 || YP::YPSpur_initex(key_) < 0)
662  {
663  std::vector<std::string> args =
664  {
665  ypspur_bin_,
666  "-d", port_,
667  "--admask", ad_mask,
668  "--msq-key", std::to_string(key_)
669  };
670  if (digital_input_enable_)
671  args.push_back(std::string("--enable-get-digital-io"));
672  if (simulate_)
673  args.push_back(std::string("--without-device"));
674  if (param_file_.size() > 0)
675  {
676  args.push_back(std::string("-p"));
677  args.push_back(param_file_);
678  }
679 
680  char **argv = new char *[args.size() + 1];
681  for (unsigned int i = 0; i < args.size(); i++)
682  {
683  argv[i] = new char[args[i].size() + 1];
684  memcpy(argv[i], args[i].c_str(), args[i].size());
685  argv[i][args[i].size()] = 0;
686  }
687  argv[args.size()] = nullptr;
688 
689  int msq = msgget(key_, 0666 | IPC_CREAT);
690  msgctl(msq, IPC_RMID, nullptr);
691 
692  ROS_WARN("launching ypspur-coordinator");
693  pid_ = fork();
694  if (pid_ == -1)
695  {
696  const int err = errno;
697  throw(std::runtime_error(std::string("failed to fork process: ") + strerror(err)));
698  }
699  else if (pid_ == 0)
700  {
701  execvp(ypspur_bin_.c_str(), argv);
702  throw(std::runtime_error("failed to start ypspur-coordinator"));
703  }
704 
705  for (unsigned int i = 0; i < args.size(); i++)
706  delete argv[i];
707  delete argv;
708 
709  for (int i = 4; i >= 0; i--)
710  {
711  int status;
712  if (waitpid(pid_, &status, WNOHANG) == pid_)
713  {
714  throw(std::runtime_error("ypspur-coordinator dead immediately"));
715  }
716  else if (i == 0)
717  {
718  throw(std::runtime_error("failed to init libypspur"));
719  }
721  if (YP::YPSpur_initex(key_) >= 0)
722  break;
723  }
724  }
725  double ret;
726  boost::atomic<bool> done(false);
727  auto get_vel_thread = [&ret, &done]
728  {
729  double test_v, test_w;
730  ret = YP::YPSpur_get_vel(&test_v, &test_w);
731  done = true;
732  };
733  boost::thread spur_test = boost::thread(get_vel_thread);
734  ros::WallDuration(0.1).sleep();
735  if (!done)
736  {
737  // There is no way to kill thread safely in C++11
738  // So, just leave it detached.
739  spur_test.detach();
740  ROS_WARN("ypspur-coordinator seems to be down - launching");
741  continue;
742  }
743  spur_test.join();
744  if (ret < 0)
745  {
746  ROS_WARN("ypspur-coordinator returns error - launching");
747  continue;
748  }
749  ROS_WARN("ypspur-coordinator launched");
750  break;
751  }
752 
753  ROS_INFO("ypspur-coordinator conneceted");
754  signal(SIGINT, sigintHandler);
755 
756  YP::YP_get_parameter(YP::YP_PARAM_MAX_VEL, &params_["vel"]);
757  YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_V, &params_["acc"]);
758  YP::YP_get_parameter(YP::YP_PARAM_MAX_W, &params_["angvel"]);
759  YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_W, &params_["angacc"]);
760 
761  if (!pnh_.hasParam("vel"))
762  ROS_WARN("default \"vel\" %0.3f used", (float)params_["vel"]);
763  if (!pnh_.hasParam("acc"))
764  ROS_WARN("default \"acc\" %0.3f used", (float)params_["acc"]);
765  if (!pnh_.hasParam("angvel"))
766  ROS_WARN("default \"angvel\" %0.3f used", (float)params_["angvel"]);
767  if (!pnh_.hasParam("angacc"))
768  ROS_WARN("default \"angacc\" %0.3f used", (float)params_["angacc"]);
769 
770  pnh_.param("vel", params_["vel"], params_["vel"]);
771  pnh_.param("acc", params_["acc"], params_["acc"]);
772  pnh_.param("angvel", params_["angvel"], params_["angvel"]);
773  pnh_.param("angacc", params_["angacc"], params_["angacc"]);
774 
775  YP::YPSpur_set_vel(params_["vel"]);
776  YP::YPSpur_set_accel(params_["acc"]);
777  YP::YPSpur_set_angvel(params_["angvel"]);
778  YP::YPSpur_set_angaccel(params_["angacc"]);
779 
780  YP::YP_set_io_data(dio_output_);
781  YP::YP_set_io_dir(dio_dir_);
782  }
784  {
785  if (pid_ > 0)
786  {
787  ROS_INFO("killing ypspur-coordinator (%d)", (int)pid_);
788  kill(pid_, SIGINT);
789  int status;
790  waitpid(pid_, &status, 0);
791  ROS_INFO("ypspur-coordinator is killed (status: %d)", status);
792  }
793  ros::shutdown();
794  }
795  void spin()
796  {
797  geometry_msgs::TransformStamped odom_trans;
798  odom_trans.header.frame_id = frames_["odom"];
799  odom_trans.child_frame_id = frames_["base_link"];
800 
801  nav_msgs::Odometry odom;
802  geometry_msgs::WrenchStamped wrench;
803  odom.header.frame_id = frames_["odom"];
804  odom.child_frame_id = frames_["base_link"];
805  wrench.header.frame_id = frames_["base_link"];
806 
807  odom.pose.pose.position.x = 0;
808  odom.pose.pose.position.y = 0;
809  odom.pose.pose.position.z = 0;
810  odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(0);
811  odom.twist.twist.linear.x = 0;
812  odom.twist.twist.linear.y = 0;
813  odom.twist.twist.angular.z = 0;
814 
815  std::map<int, geometry_msgs::TransformStamped> joint_trans;
816  sensor_msgs::JointState joint;
817  if (joints_.size() > 0)
818  {
819  joint.header.frame_id = std::string("");
820  joint.velocity.resize(joints_.size());
821  joint.position.resize(joints_.size());
822  joint.effort.resize(joints_.size());
823  for (auto &j : joints_)
824  joint.name.push_back(j.name_);
825 
826  for (unsigned int i = 0; i < joints_.size(); i++)
827  {
828  joint_trans[i].header.frame_id = joints_[i].name_ + std::string("_in");
829  joint_trans[i].child_frame_id = joints_[i].name_ + std::string("_out");
830  joint.velocity[i] = 0;
831  joint.position[i] = 0;
832  joint.effort[i] = 0;
833  }
834  }
835 
836  ROS_INFO("ypspur_ros main loop started");
837  ros::Rate loop(params_["hz"]);
838  while (!g_shutdown)
839  {
840  const auto now = ros::Time::now();
841  const float dt = 1.0 / params_["hz"];
842 
843  if (cmd_vel_ && cmd_vel_expire_ > ros::Duration(0))
844  {
845  if (cmd_vel_time_ + cmd_vel_expire_ < now)
846  {
847  // cmd_vel is too old and expired
848  cmd_vel_ = nullptr;
849  if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
850  YP::YPSpur_vel(0.0, 0.0);
851  }
852  }
853 
854  if (mode_ == DIFF)
855  {
856  double x, y, yaw, v(0), w(0);
857  double t;
858 
859  if (!simulate_control_)
860  {
861  t = YP::YPSpur_get_pos(YP::CS_BS, &x, &y, &yaw);
862  if (t == 0.0)
863  t = now.toSec();
864  YP::YPSpur_get_vel(&v, &w);
865  }
866  else
867  {
868  t = ros::Time::now().toSec();
869  if (cmd_vel_)
870  {
871  v = cmd_vel_->linear.x;
872  w = cmd_vel_->angular.z;
873  }
874  yaw = tf::getYaw(odom.pose.pose.orientation) + dt * w;
875  x = odom.pose.pose.position.x + dt * v * cosf(yaw);
876  y = odom.pose.pose.position.y + dt * v * sinf(yaw);
877  }
878 
879  odom.header.stamp = ros::Time(t);
880  odom.pose.pose.position.x = x;
881  odom.pose.pose.position.y = y;
882  odom.pose.pose.position.z = 0;
883  odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
884  odom.twist.twist.linear.x = v;
885  odom.twist.twist.linear.y = 0;
886  odom.twist.twist.angular.z = w;
887  pubs_["odom"].publish(odom);
888 
889  odom_trans.header.stamp = ros::Time(t) + ros::Duration(tf_time_offset_);
890  odom_trans.transform.translation.x = x;
891  odom_trans.transform.translation.y = y;
892  odom_trans.transform.translation.z = 0;
893  odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(yaw);
894  tf_broadcaster_.sendTransform(odom_trans);
895 
896  t = YP::YPSpur_get_force(&wrench.wrench.force.x, &wrench.wrench.torque.z);
897  if (t == 0.0)
898  t = now.toSec();
899  wrench.header.stamp = ros::Time(t);
900  wrench.wrench.force.y = 0;
901  wrench.wrench.force.z = 0;
902  wrench.wrench.torque.x = 0;
903  wrench.wrench.torque.y = 0;
904  pubs_["wrench"].publish(wrench);
905 
906  if (frames_["origin"].length() > 0)
907  {
908  try
909  {
910  tf::StampedTransform transform;
911  tf_listener_.lookupTransform(
912  frames_["origin"], frames_["base_link"],
913  ros::Time(0), transform);
914 
915  tfScalar yaw, pitch, roll;
916  transform.getBasis().getEulerYPR(yaw, pitch, roll);
917  YP::YPSpur_adjust_pos(YP::CS_GL, transform.getOrigin().x(),
918  transform.getOrigin().y(),
919  yaw);
920  }
921  catch (tf::TransformException ex)
922  {
923  ROS_ERROR("Failed to feedback localization result to YP-Spur (%s)", ex.what());
924  }
925  }
926  }
927  if (joints_.size() > 0)
928  {
929  double t;
930  if (!simulate_control_)
931  {
932 #if !(YPSPUR_JOINT_SUPPORT)
933  while (1)
934  {
935  double js[2];
936  int i;
937  t = YP::YP_get_wheel_ang(&js[0], &js[1]);
938  i = 0;
939  for (auto &j : joints_)
940  joint.position[i++] = js[j.id_];
941  if (t != YP::YP_get_wheel_vel(&js[0], &js[1]))
942  continue;
943  i = 0;
944  for (auto &j : joints_)
945  joint.velocity[i++] = js[j.id_];
946  if (t != YP::YP_get_wheel_torque(&js[0], &js[1]))
947  continue;
948  i = 0;
949  for (auto &j : joints_)
950  joint.effort[i++] = js[j.id_];
951 
952  if (t == 0.0)
953  t = ros::Time::now().toSec();
954  break;
955  }
956 #else
957  t = -1.0;
958  while (t < 0.0)
959  {
960  int i = 0;
961  for (auto &j : joints_)
962  {
963  const double t0 = YP::YP_get_joint_ang(j.id_, &joint.position[i]);
964  const double t1 = YP::YP_get_joint_vel(j.id_, &joint.velocity[i]);
965  const double t2 = YP::YP_get_joint_torque(j.id_, &joint.effort[i]);
966 
967  if (t0 != t1 || t1 != t2)
968  {
969  // Retry if updated during this joint
970  t = -1.0;
971  break;
972  }
973  if (t < 0.0)
974  {
975  t = t0;
976  }
977  else if (t != t0)
978  {
979  // Retry if updated during loops
980  t = -1.0;
981  break;
982  }
983  i++;
984  }
985  if (t == 0.0)
986  t = ros::Time::now().toSec();
987  }
988 #endif
989  joint.header.stamp = ros::Time(t);
990  }
991  else
992  {
993  t = ros::Time::now().toSec();
994  for (unsigned int i = 0; i < joints_.size(); i++)
995  {
996  auto vel_prev = joint.velocity[i];
997  switch (joints_[i].control_)
998  {
999  case JointParams::STOP:
1000  break;
1001  case JointParams::TRAJECTORY:
1002  case JointParams::POSITION:
1003  case JointParams::VELOCITY:
1004  switch (joints_[i].control_)
1005  {
1006  case JointParams::POSITION:
1007  {
1008  float position_err = joints_[i].angle_ref_ - joint.position[i];
1009  joints_[i].vel_ref_ = sqrtf(2.0 * joints_[i].accel_ * fabs(position_err));
1010  if (joints_[i].vel_ref_ > joints_[i].vel_)
1011  joints_[i].vel_ref_ = joints_[i].vel_;
1012  if (position_err < 0)
1013  joints_[i].vel_ref_ = -joints_[i].vel_ref_;
1014  }
1015  break;
1016  case JointParams::TRAJECTORY:
1017  {
1018  float position_err = joints_[i].angle_ref_ - joint.position[i];
1019  float v_sq = joints_[i].vel_end_ * joints_[i].vel_end_ + 2.0 * joints_[i].accel_ * position_err;
1020  joints_[i].vel_ref_ = sqrtf(fabs(v_sq));
1021 
1022  float vel_max;
1023  if (fabs(joints_[i].vel_) < fabs(joints_[i].vel_end_))
1024  {
1025  if (fabs(position_err) <
1026  (joints_[i].vel_end_ * joints_[i].vel_end_ - joints_[i].vel_ * joints_[i].vel_) /
1027  (2.0 * joints_[i].accel_))
1028  vel_max = fabs(joints_[i].vel_end_);
1029  else
1030  vel_max = joints_[i].vel_;
1031  }
1032  else
1033  vel_max = joints_[i].vel_;
1034 
1035  if (joints_[i].vel_ref_ > vel_max)
1036  joints_[i].vel_ref_ = vel_max;
1037  if (position_err < 0)
1038  joints_[i].vel_ref_ = -joints_[i].vel_ref_;
1039  }
1040  break;
1041  default:
1042  break;
1043  }
1044  joint.velocity[i] = joints_[i].vel_ref_;
1045  if (joint.velocity[i] < vel_prev - dt * joints_[i].accel_)
1046  {
1047  joint.velocity[i] = vel_prev - dt * joints_[i].accel_;
1048  }
1049  else if (joint.velocity[i] > vel_prev + dt * joints_[i].accel_)
1050  {
1051  joint.velocity[i] = vel_prev + dt * joints_[i].accel_;
1052  }
1053  joint.position[i] += joint.velocity[i] * dt;
1054  break;
1055  }
1056  }
1057  joint.header.stamp = ros::Time(t);
1058  }
1059  pubs_["joint"].publish(joint);
1060 
1061  for (unsigned int i = 0; i < joints_.size(); i++)
1062  {
1063  joint_trans[i].transform.rotation =
1064  tf::createQuaternionMsgFromYaw(joint.position[i]);
1065  joint_trans[i].header.stamp = ros::Time(t) + ros::Duration(tf_time_offset_);
1066  tf_broadcaster_.sendTransform(joint_trans[i]);
1067  }
1068 
1069 #if (YPSPUR_JOINT_ANG_VEL_SUPPORT)
1070  for (unsigned int jid = 0; jid < joints_.size(); jid++)
1071  {
1072  if (joints_[jid].control_ != JointParams::TRAJECTORY)
1073  continue;
1074 
1075  auto &cmd_joint_ = joints_[jid].cmd_joint_;
1076  auto t = now - cmd_joint_.header.stamp;
1077  if (t < ros::Duration(0))
1078  continue;
1079 
1080  bool done = true;
1081  for (auto &cmd : cmd_joint_.points)
1082  {
1083  if (cmd.time_from_start < ros::Duration(0))
1084  continue;
1085  if (now > cmd_joint_.header.stamp + cmd.time_from_start)
1086  continue;
1087  done = false;
1088 
1089  double ang_err = cmd.positions[0] - joint.position[jid];
1090  double &vel_end_ = cmd.velocities[0];
1091  double &vel_start = joint.velocity[jid];
1092  auto t_left = cmd.time_from_start - t;
1093 
1094  double v;
1095  double v_min;
1096  bool v_found = true;
1097  while (true)
1098  {
1099  // ROS_INFO("st: %0.3f, en: %0.3f, err: %0.3f, t: %0.3f",
1100  // vel_start, vel_end_, ang_err, t_left.toSec());
1101  int s;
1102  if (vel_end_ > vel_start)
1103  s = 1;
1104  else
1105  s = -1;
1106  v = (s * (vel_start + vel_end_) * (vel_start - vel_end_) +
1107  ang_err * joints_[jid].accel_ * 2.0) /
1108  (2.0 * s * (vel_start - vel_end_) + joints_[jid].accel_ * 2.0 * (t_left.toSec()));
1109 
1110  double err_deacc;
1111  err_deacc = fabs(vel_end_ * vel_end_ - v * v) / (joints_[jid].accel_ * 2.0);
1112  // ROS_INFO("v+-: %0.3f", v);
1113  v_min = fabs(v);
1114  if ((vel_start * s <= v * s || err_deacc >= fabs(ang_err)) &&
1115  v * s <= vel_end_ * s)
1116  break;
1117 
1118  v_min = DBL_MAX;
1119 
1120  auto vf = [](const double &st, const double &en,
1121  const double &acc, const double &err, const double &t,
1122  const int &sig, const int &sol, double &ret)
1123  {
1124  double sq;
1125  sq = -4.0 * st * st +
1126  8.0 * st * en -
1127  4.0 * en * en +
1128  4.0 * sig * acc * 2 * (t * (st + en) - 2.0 * err) +
1129  4.0 * acc * acc * t * t;
1130  if (sq < 0)
1131  return false;
1132 
1133  ret = (2.0 * sig * (st + en) + 2.0 * acc * t + sol * sqrt(sq)) / (4.0 * sig);
1134 
1135  return true;
1136  };
1137 
1138  v_found = false;
1139 
1140  if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1141  1, 1, v))
1142  {
1143  // ROS_INFO("v++: sol+ %0.3f", v);
1144  if (v >= vel_start && v >= vel_end_)
1145  {
1146  if (v_min > fabs(v))
1147  v_min = fabs(v);
1148  v_found = true;
1149  }
1150  }
1151  if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1152  -1, 1, v))
1153  {
1154  // ROS_INFO("v--: sol+ %0.3f", v);
1155  if (v <= vel_start && v <= vel_end_)
1156  {
1157  if (v_min > fabs(v))
1158  v_min = fabs(v);
1159  v_found = true;
1160  }
1161  }
1162  if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1163  1, -1, v))
1164  {
1165  // ROS_INFO("v++: sol- %0.3f", v);
1166  if (v >= vel_start && v >= vel_end_)
1167  {
1168  if (v_min > fabs(v))
1169  v_min = fabs(v);
1170  v_found = true;
1171  }
1172  }
1173  if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1174  -1, -1, v))
1175  {
1176  // ROS_INFO("v--: sol- %0.3f", v);
1177  if (v <= vel_start && v <= vel_end_)
1178  {
1179  if (v_min > fabs(v))
1180  v_min = fabs(v);
1181  v_found = true;
1182  }
1183  }
1184  break;
1185  }
1186  if (v_found)
1187  {
1188  // ROS_INFO("v: %0.3f", v_min);
1189  joints_[jid].angle_ref_ = cmd.positions[0];
1190  joints_[jid].vel_end_ = vel_end_;
1191  joints_[jid].vel_ = v_min;
1192 
1193  YP::YP_set_joint_vel(joints_[jid].id_, v_min);
1194  YP::YP_set_joint_accel(joints_[jid].id_, joints_[jid].accel_);
1195  YP::YP_joint_ang_vel(joints_[jid].id_, cmd.positions[0], vel_end_);
1196  }
1197  else
1198  {
1199  ROS_ERROR("Impossible trajectory given");
1200  }
1201  break;
1202  }
1203 
1204  if (done)
1205  {
1206  if ((joints_[jid].vel_end_ > 0.0 &&
1207  joints_[jid].angle_ref_ > joint.position[jid] &&
1208  joints_[jid].angle_ref_ < joint.position[jid] + joints_[jid].vel_ref_ * dt) ||
1209  (joints_[jid].vel_end_ < 0.0 &&
1210  joints_[jid].angle_ref_ < joint.position[jid] &&
1211  joints_[jid].angle_ref_ > joint.position[jid] + joints_[jid].vel_ref_ * dt))
1212  {
1213  joints_[jid].control_ = JointParams::VELOCITY;
1214  joints_[jid].vel_ref_ = joints_[jid].vel_end_;
1215  }
1216  }
1217  }
1218 #endif
1219  }
1220 
1221  for (int i = 0; i < ad_num_; i++)
1222  {
1223  if (ads_[i].enable_)
1224  {
1225  std_msgs::Float32 ad;
1226  ad.data = YP::YP_get_ad_value(i) * ads_[i].gain_ + ads_[i].offset_;
1227  pubs_["ad/" + ads_[i].name_].publish(ad);
1228  }
1229  }
1230 
1231  if (digital_input_enable_)
1232  {
1233  ypspur_ros::DigitalInput din;
1234 
1235  din.header.stamp = ros::Time::now();
1236  int in = YP::YP_get_ad_value(15);
1237  for (int i = 0; i < dio_num_; i++)
1238  {
1239  if (!dios_[i].enable_)
1240  continue;
1241  din.name.push_back(dios_[i].name_);
1242  if (in & (1 << i))
1243  din.state.push_back(true);
1244  else
1245  din.state.push_back(false);
1246  }
1247  pubs_["din"].publish(din);
1248  }
1249 
1250  for (int i = 0; i < dio_num_; i++)
1251  {
1252  if (dio_revert_[i] != ros::Time(0))
1253  {
1254  if (dio_revert_[i] < now)
1255  {
1256  revertDigitalOutput(i);
1257  }
1258  }
1259  }
1260  updateDiagnostics(now);
1261 
1262  if (YP::YP_get_error_state())
1263  {
1264  ROS_ERROR("ypspur-coordinator is not active");
1265  break;
1266  }
1267  ros::spinOnce();
1268  loop.sleep();
1269 
1270  int status;
1271  if (waitpid(pid_, &status, WNOHANG) == pid_)
1272  {
1273  if (WIFEXITED(status))
1274  {
1275  ROS_ERROR("ypspur-coordinator exited");
1276  }
1277  else
1278  {
1279  if (WIFSTOPPED(status))
1280  {
1281  ROS_ERROR("ypspur-coordinator dead with signal %d",
1282  WSTOPSIG(status));
1283  }
1284  else
1285  {
1286  ROS_ERROR("ypspur-coordinator dead");
1287  }
1288  updateDiagnostics(now, true);
1289  }
1290  break;
1291  }
1292  }
1293  ROS_INFO("ypspur_ros main loop terminated");
1294  }
1295 };
1296 
1297 int main(int argc, char *argv[])
1298 {
1299  ros::init(argc, argv, "ypspur_ros");
1300 
1301  try
1302  {
1303  YpspurRosNode yr;
1304  yr.spin();
1305  }
1306  catch (std::runtime_error &e)
1307  {
1308  ROS_ERROR("%s", e.what());
1309  return -1;
1310  }
1311 
1312  return 0;
1313 }
int main(int argc, char *argv[])
std::map< std::string, int > joint_name_to_num_
Definition: ypspur_ros.cpp:129
void cbVel(const std_msgs::Float32::ConstPtr &msg, int num)
Definition: ypspur_ros.cpp:271
bool param(const std::string &param_name, T &param_val, const T &default_val)
tf::TransformBroadcaster tf_broadcaster_
Definition: ypspur_ros.cpp:87
void cbJointPosition(const ypspur_ros::JointPositionControl::ConstPtr &msg)
Definition: ypspur_ros.cpp:292
std::vector< AdParams > ads_
Definition: ypspur_ros.cpp:148
void updateDiagnostics(const ros::Time &now, const bool connection_down=false)
Definition: ypspur_ros.cpp:379
double tfScalar
std::map< std::string, double > params_
Definition: ypspur_ros.cpp:93
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
void sigintHandler(int sig)
Definition: ypspur_ros.cpp:74
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
Definition: ypspur_ros.cpp:183
static double getYaw(const Quaternion &bt_q)
std::map< int, ros::Time > dio_revert_
Definition: ypspur_ros.cpp:156
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::NodeHandle nh_
Definition: ypspur_ros.cpp:82
std::string ypspur_bin_
Definition: ypspur_ros.cpp:91
std::string param_file_
Definition: ypspur_ros.cpp:90
std::vector< DioParams > dios_
Definition: ypspur_ros.cpp:149
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
int ad[16]
TFSIMD_FORCE_INLINE const tfScalar & x() const
trajectory_msgs::JointTrajectory cmd_joint_
Definition: ypspur_ros.cpp:126
std::vector< JointParams > joints_
Definition: ypspur_ros.cpp:128
bool sleep() const
void cbControlMode(const ypspur_ros::ControlMode::ConstPtr &msg)
Definition: ypspur_ros.cpp:168
void cbAngle(const std_msgs::Float32::ConstPtr &msg, int num)
Definition: ypspur_ros.cpp:282
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
ros::NodeHandle pnh_
Definition: ypspur_ros.cpp:83
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool digital_input_enable_
Definition: ypspur_ros.cpp:147
bool g_shutdown
Definition: ypspur_ros.cpp:73
ros::Time cmd_vel_time_
Definition: ypspur_ros.cpp:163
TFSIMD_FORCE_INLINE const tfScalar & y() const
OdometryMode mode_
Definition: ypspur_ros.cpp:107
void sendTransform(const StampedTransform &transform)
std::map< std::string, std::string > frames_
Definition: ypspur_ros.cpp:92
unsigned int dio_output_default_
Definition: ypspur_ros.cpp:153
TFSIMD_FORCE_INLINE const tfScalar & x() const
double tf_time_offset_
Definition: ypspur_ros.cpp:98
bool simulate_control_
Definition: ypspur_ros.cpp:96
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cbSetVel(const std_msgs::Float32::ConstPtr &msg, int num)
Definition: ypspur_ros.cpp:251
std::string port_
Definition: ypspur_ros.cpp:89
std::map< std::string, ros::Publisher > pubs_
Definition: ypspur_ros.cpp:84
tf::TransformListener tf_listener_
Definition: ypspur_ros.cpp:86
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
ros::Duration cmd_vel_expire_
Definition: ypspur_ros.cpp:164
bool sleep()
TFSIMD_FORCE_INLINE const tfScalar & w() const
unsigned int dio_dir_
Definition: ypspur_ros.cpp:152
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
unsigned int dio_dir_default_
Definition: ypspur_ros.cpp:154
ros::Time device_error_state_time_
Definition: ypspur_ros.cpp:160
void cbJoint(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
Definition: ypspur_ros.cpp:192
void cbSetAccel(const std_msgs::Float32::ConstPtr &msg, int num)
Definition: ypspur_ros.cpp:261
void checkCompatMode()
Definition: compatibility.h:60
int device_error_state_
Definition: ypspur_ros.cpp:158
static Time now()
ROSCPP_DECL void shutdown()
double p(YPSpur_param id, enum motor_id motor)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
const std::string header
bool hasParam(const std::string &key) const
int device_error_state_prev_
Definition: ypspur_ros.cpp:159
unsigned int dio_output_
Definition: ypspur_ros.cpp:151
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
Definition: compatibility.h:98
ROSCPP_DECL void spinOnce()
void cbDigitalOutput(const ypspur_ros::DigitalOutput::ConstPtr &msg, int id_)
Definition: ypspur_ros.cpp:323
#define ROS_ERROR(...)
geometry_msgs::Twist::ConstPtr cmd_vel_
Definition: ypspur_ros.cpp:162
std::map< std::string, ros::Subscriber > subs_
Definition: ypspur_ros.cpp:85
void revertDigitalOutput(int id_)
Definition: ypspur_ros.cpp:361


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 19:41:30