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


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Mon Feb 19 2024 03:32:25