ypspur_ros.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2015-2017, the ypspur_ros authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <diagnostic_msgs/DiagnosticArray.h>
00033 #include <geometry_msgs/Twist.h>
00034 #include <geometry_msgs/WrenchStamped.h>
00035 #include <nav_msgs/Odometry.h>
00036 #include <sensor_msgs/JointState.h>
00037 #include <std_msgs/Bool.h>
00038 #include <std_msgs/Float32.h>
00039 #include <std_msgs/Float32MultiArray.h>
00040 #include <trajectory_msgs/JointTrajectory.h>
00041 #include <ypspur_ros/ControlMode.h>
00042 #include <ypspur_ros/DigitalInput.h>
00043 #include <ypspur_ros/DigitalOutput.h>
00044 #include <ypspur_ros/JointPositionControl.h>
00045 
00046 #include <tf/transform_broadcaster.h>
00047 #include <tf/transform_listener.h>
00048 
00049 #include <signal.h>
00050 #include <string.h>
00051 #include <sys/ipc.h>
00052 #include <sys/msg.h>
00053 #include <sys/types.h>
00054 #include <sys/wait.h>
00055 
00056 #include <boost/atomic.hpp>
00057 #include <boost/chrono.hpp>
00058 #include <boost/thread.hpp>
00059 #include <boost/thread/future.hpp>
00060 
00061 #include <exception>
00062 #include <map>
00063 #include <string>
00064 #include <vector>
00065 
00066 #include <compatibility.h>
00067 
00068 namespace YP
00069 {
00070 #include <ypspur.h>
00071 }  // namespace YP
00072 
00073 bool g_shutdown = false;
00074 void sigintHandler(int sig)
00075 {
00076   g_shutdown = true;
00077 }
00078 
00079 class YpspurRosNode
00080 {
00081 private:
00082   ros::NodeHandle nh_;
00083   ros::NodeHandle pnh_;
00084   std::map<std::string, ros::Publisher> pubs_;
00085   std::map<std::string, ros::Subscriber> subs_;
00086   tf::TransformListener tf_listener_;
00087   tf::TransformBroadcaster tf_broadcaster_;
00088 
00089   std::string port_;
00090   std::string param_file_;
00091   std::string ypspur_bin_;
00092   std::map<std::string, std::string> frames_;
00093   std::map<std::string, double> params_;
00094   int key_;
00095   bool simulate_;
00096   bool simulate_control_;
00097 
00098   double tf_time_offset_;
00099 
00100   pid_t pid_;
00101 
00102   enum OdometryMode
00103   {
00104     DIFF,
00105     NONE
00106   };
00107   OdometryMode mode_;
00108   class JointParams
00109   {
00110   public:
00111     int id_;
00112     std::string name_;
00113     double accel_;
00114     double vel_;
00115     double angle_ref_;
00116     double vel_ref_;
00117     double vel_end_;
00118     enum control_mode_
00119     {
00120       STOP,
00121       VELOCITY,
00122       POSITION,
00123       TRAJECTORY
00124     };
00125     control_mode_ control_;
00126     trajectory_msgs::JointTrajectory cmd_joint_;
00127   };
00128   std::vector<JointParams> joints_;
00129   std::map<std::string, int> joint_name_to_num_;
00130 
00131   class AdParams
00132   {
00133   public:
00134     bool enable_;
00135     std::string name_;
00136     double gain_;
00137     double offset_;
00138   };
00139   class DioParams
00140   {
00141   public:
00142     bool enable_;
00143     std::string name_;
00144     bool input_;
00145     bool output_;
00146   };
00147   bool digital_input_enable_;
00148   std::vector<AdParams> ads_;
00149   std::vector<DioParams> dios_;
00150   const int ad_num_ = 8;
00151   unsigned int dio_output_;
00152   unsigned int dio_dir_;
00153   unsigned int dio_output_default_;
00154   unsigned int dio_dir_default_;
00155   const int dio_num_ = 8;
00156   std::map<int, ros::Time> dio_revert_;
00157 
00158   int device_error_state_;
00159   int device_error_state_prev_;
00160   ros::Time device_error_state_time_;
00161 
00162   geometry_msgs::Twist::ConstPtr cmd_vel_;
00163   ros::Time cmd_vel_time_;
00164   ros::Duration cmd_vel_expire_;
00165 
00166   int control_mode_;
00167 
00168   void cbControlMode(const ypspur_ros::ControlMode::ConstPtr &msg)
00169   {
00170     control_mode_ = msg->vehicle_control_mode;
00171     switch (control_mode_)
00172     {
00173       case ypspur_ros::ControlMode::OPEN:
00174         YP::YP_openfree();
00175         break;
00176       case ypspur_ros::ControlMode::TORQUE:
00177         YP::YPSpur_free();
00178         break;
00179       case ypspur_ros::ControlMode::VELOCITY:
00180         break;
00181     }
00182   }
00183   void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
00184   {
00185     cmd_vel_ = msg;
00186     cmd_vel_time_ = ros::Time::now();
00187     if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
00188     {
00189       YP::YPSpur_vel(msg->linear.x, msg->angular.z);
00190     }
00191   }
00192   void cbJoint(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
00193   {
00194 #if !(YPSPUR_JOINT_ANG_VEL_SUPPORT)
00195     ROS_ERROR("JointTrajectory command is not available on this YP-Spur version");
00196 #endif
00197     const ros::Time now = ros::Time::now();
00198 
00199     std_msgs::Header header = msg->header;
00200     if (header.stamp == ros::Time(0))
00201       header.stamp = now;
00202 
00203     std::map<std::string, trajectory_msgs::JointTrajectory> new_cmd_joints;
00204     size_t i = 0;
00205     for (const std::string &name : msg->joint_names)
00206     {
00207       trajectory_msgs::JointTrajectory cmd_joint;
00208       cmd_joint.header = header;
00209       cmd_joint.joint_names.resize(1);
00210       cmd_joint.joint_names[0] = name;
00211       cmd_joint.points.clear();
00212       std::string err_msg;
00213       for (auto &cmd : msg->points)
00214       {
00215         if (header.stamp + cmd.time_from_start < now)
00216         {
00217           ROS_ERROR(
00218               "Ignored outdated JointTrajectory command "
00219               "(joint: %s, now: %0.6lf, stamp: %0.6lf, time_from_start: %0.6lf)",
00220               name.c_str(), now.toSec(), header.stamp.toSec(), cmd.time_from_start.toSec());
00221           break;
00222         }
00223 
00224         trajectory_msgs::JointTrajectoryPoint p;
00225         p.time_from_start = cmd.time_from_start;
00226         p.positions.resize(1);
00227         p.velocities.resize(1);
00228         if (cmd.velocities.size() <= i)
00229           p.velocities[0] = 0.0;
00230         else
00231           p.velocities[0] = cmd.velocities[i];
00232         p.positions[0] = cmd.positions[i];
00233 
00234         cmd_joint.points.push_back(p);
00235       }
00236       i++;
00237 
00238       if (cmd_joint.points.size() != msg->points.size())
00239         return;
00240 
00241       new_cmd_joints[name] = cmd_joint;
00242     }
00243     // Apply if all JointTrajectoryPoints are valid
00244     for (auto &new_cmd_joint : new_cmd_joints)
00245     {
00246       const int joint_num = joint_name_to_num_[new_cmd_joint.first];
00247       joints_[joint_num].control_ = JointParams::TRAJECTORY;
00248       joints_[joint_num].cmd_joint_ = new_cmd_joint.second;
00249     }
00250   }
00251   void cbSetVel(const std_msgs::Float32::ConstPtr &msg, int num)
00252   {
00253     // printf("set_vel %d %d %f\n", num, joints_[num].id_, msg->data);
00254     joints_[num].vel_ = msg->data;
00255 #if !(YPSPUR_JOINT_SUPPORT)
00256     YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
00257 #else
00258     YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
00259 #endif
00260   }
00261   void cbSetAccel(const std_msgs::Float32::ConstPtr &msg, int num)
00262   {
00263     // printf("set_accel %d %d %f\n", num, joints_[num].id_, msg->data);
00264     joints_[num].accel_ = msg->data;
00265 #if !(YPSPUR_JOINT_SUPPORT)
00266     YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
00267 #else
00268     YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
00269 #endif
00270   }
00271   void cbVel(const std_msgs::Float32::ConstPtr &msg, int num)
00272   {
00273     // printf("vel_ %d %d %f\n", num, joints_[num].id_, msg->data);
00274     joints_[num].vel_ref_ = msg->data;
00275     joints_[num].control_ = JointParams::VELOCITY;
00276 #if !(YPSPUR_JOINT_SUPPORT)
00277     YP::YP_wheel_vel(joints_[0].vel_ref_, joints_[1].vel_ref_);
00278 #else
00279     YP::YP_joint_vel(joints_[num].id_, joints_[num].vel_ref_);
00280 #endif
00281   }
00282   void cbAngle(const std_msgs::Float32::ConstPtr &msg, int num)
00283   {
00284     joints_[num].angle_ref_ = msg->data;
00285     joints_[num].control_ = JointParams::POSITION;
00286 #if !(YPSPUR_JOINT_SUPPORT)
00287     YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
00288 #else
00289     YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
00290 #endif
00291   }
00292   void cbJointPosition(const ypspur_ros::JointPositionControl::ConstPtr &msg)
00293   {
00294     int i = 0;
00295     for (auto &name : msg->joint_names)
00296     {
00297       if (joint_name_to_num_.find(name) == joint_name_to_num_.end())
00298       {
00299         ROS_ERROR("Unknown joint name '%s'", name.c_str());
00300         continue;
00301       }
00302       int num = joint_name_to_num_[name];
00303       // printf("%s %d %d  %f", name.c_str(), num, joints_[num].id_, msg->positions[i]);
00304       joints_[num].vel_ = msg->velocities[i];
00305       joints_[num].accel_ = msg->accelerations[i];
00306       joints_[num].angle_ref_ = msg->positions[i];
00307       joints_[num].control_ = JointParams::POSITION;
00308 
00309 #if (YPSPUR_JOINT_SUPPORT)
00310       YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
00311       YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
00312       YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
00313 #endif
00314       i++;
00315     }
00316 #if !(YPSPUR_JOINT_SUPPORT)
00317     YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
00318     YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
00319     YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
00320 #endif
00321   }
00322 
00323   void cbDigitalOutput(const ypspur_ros::DigitalOutput::ConstPtr &msg, int id_)
00324   {
00325     const auto dio_output_prev = dio_output_;
00326     const auto dio_dir_prev = dio_dir_;
00327     const unsigned int mask = 1 << id_;
00328 
00329     switch (msg->output)
00330     {
00331       case ypspur_ros::DigitalOutput::HIGH_IMPEDANCE:
00332         dio_output_ &= ~mask;
00333         dio_dir_ &= ~mask;
00334         break;
00335       case ypspur_ros::DigitalOutput::LOW:
00336         dio_output_ &= ~mask;
00337         dio_dir_ |= mask;
00338         break;
00339       case ypspur_ros::DigitalOutput::HIGH:
00340         dio_output_ |= mask;
00341         dio_dir_ |= mask;
00342         break;
00343       case ypspur_ros::DigitalOutput::PULL_UP:
00344         dio_output_ |= mask;
00345         dio_dir_ &= ~mask;
00346         break;
00347       case ypspur_ros::DigitalOutput::PULL_DOWN:
00348         ROS_ERROR("Digital IO pull down is not supported on this system");
00349         break;
00350     }
00351     if (dio_output_ != dio_output_prev)
00352       YP::YP_set_io_data(dio_output_);
00353     if (dio_dir_ != dio_dir_prev)
00354       YP::YP_set_io_dir(dio_dir_);
00355 
00356     if (msg->toggle_time > ros::Duration(0))
00357     {
00358       dio_revert_[id_] = ros::Time::now() + msg->toggle_time;
00359     }
00360   }
00361   void revertDigitalOutput(int id_)
00362   {
00363     const auto dio_output_prev = dio_output_;
00364     const auto dio_dir_prev = dio_dir_;
00365     const unsigned int mask = 1 << id_;
00366 
00367     dio_output_ &= ~mask;
00368     dio_output_ |= dio_output_default_ & mask;
00369     dio_dir_ &= ~mask;
00370     dio_dir_ |= dio_output_default_ & mask;
00371 
00372     if (dio_output_ != dio_output_prev)
00373       YP::YP_set_io_data(dio_output_);
00374     if (dio_dir_ != dio_dir_prev)
00375       YP::YP_set_io_dir(dio_dir_);
00376 
00377     dio_revert_[id_] = ros::Time(0);
00378   }
00379   void updateDiagnostics(const ros::Time &now, const bool connection_down = false)
00380   {
00381     const int connection_error = connection_down ? 1 : YP::YP_get_error_state();
00382     double t = 0;
00383 
00384 #if (YPSPUR_GET_DEVICE_ERROR_STATE_SUPPORT)
00385     int err = 0;
00386     if (!connection_error)
00387       t = YP::YP_get_device_error_state(0, &err);
00388     device_error_state_ |= err;
00389 #else
00390     ROS_WARN_ONCE(
00391         "This version of yp-spur doesn't provide device error status. "
00392         "Consider building ypspur_ros with latest yp-spur.");
00393 #endif
00394     if (device_error_state_time_ + ros::Duration(1.0) < now || connection_down ||
00395         device_error_state_ != device_error_state_prev_)
00396     {
00397       device_error_state_time_ = now;
00398       device_error_state_prev_ = device_error_state_;
00399 
00400       diagnostic_msgs::DiagnosticArray msg;
00401       msg.header.stamp = now;
00402       msg.status.resize(1);
00403       msg.status[0].name = "YP-Spur Motor Controller";
00404       msg.status[0].hardware_id = "ipc-key" + std::to_string(key_);
00405       if (device_error_state_ == 0 && connection_error == 0)
00406       {
00407         if (t == 0)
00408         {
00409           msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
00410           msg.status[0].message = "Motor controller doesn't "
00411                                   "provide device error state.";
00412         }
00413         else
00414         {
00415           if (ros::Time(t) < now - ros::Duration(1.0))
00416           {
00417             msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
00418             msg.status[0].message = "Motor controller doesn't "
00419                                     "update latest device error state.";
00420           }
00421           else
00422           {
00423             msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
00424             msg.status[0].message = "Motor controller is running without error.";
00425           }
00426         }
00427       }
00428       else
00429       {
00430         msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
00431         if (connection_error)
00432           msg.status[0].message +=
00433               "Connection to ypspur-coordinator is down.";
00434         if (device_error_state_)
00435           msg.status[0].message +=
00436               std::string((msg.status[0].message.size() > 0 ? " " : "")) +
00437               "Motor controller reported error id " +
00438               std::to_string(device_error_state_) + ".";
00439       }
00440       msg.status[0].values.resize(2);
00441       msg.status[0].values[0].key = "connection_error";
00442       msg.status[0].values[0].value = std::to_string(connection_error);
00443       msg.status[0].values[1].key = "device_error";
00444       msg.status[0].values[1].value = std::to_string(device_error_state_);
00445 
00446       pubs_["diag"].publish(msg);
00447       device_error_state_ = 0;
00448     }
00449   }
00450 
00451 public:
00452   YpspurRosNode()
00453     : nh_()
00454     , pnh_("~")
00455     , device_error_state_(0)
00456     , device_error_state_prev_(0)
00457     , device_error_state_time_(0)
00458   {
00459     compat::checkCompatMode();
00460 
00461     pnh_.param("port", port_, std::string("/dev/ttyACM0"));
00462     pnh_.param("ipc_key", key_, 28741);
00463     pnh_.param("simulate", simulate_, false);
00464     pnh_.param("simulate_control", simulate_control_, false);
00465     if (simulate_control_)
00466       simulate_ = true;
00467     pnh_.param("ypspur_bin", ypspur_bin_, std::string("ypspur-coordinator"));
00468     pnh_.param("param_file", param_file_, std::string(""));
00469     pnh_.param("tf_time_offset", tf_time_offset_, 0.0);
00470 
00471     double cmd_vel_expire_s;
00472     pnh_.param("cmd_vel_expire", cmd_vel_expire_s, -1.0);
00473     cmd_vel_expire_ = ros::Duration(cmd_vel_expire_s);
00474 
00475     std::string ad_mask("");
00476     ads_.resize(ad_num_);
00477     for (int i = 0; i < ad_num_; i++)
00478     {
00479       pnh_.param(std::string("ad") + std::to_string(i) + std::string("_enable"),
00480                  ads_[i].enable_, false);
00481       pnh_.param(std::string("ad") + std::to_string(i) + std::string("_name"),
00482                  ads_[i].name_, std::string("ad") + std::to_string(i));
00483       pnh_.param(std::string("ad") + std::to_string(i) + std::string("_gain"),
00484                  ads_[i].gain_, 1.0);
00485       pnh_.param(std::string("ad") + std::to_string(i) + std::string("_offset"),
00486                  ads_[i].offset_, 0.0);
00487       ad_mask = (ads_[i].enable_ ? std::string("1") : std::string("0")) + ad_mask;
00488       pubs_["ad/" + ads_[i].name_] = compat::advertise<std_msgs::Float32>(
00489           nh_, "ad/" + ads_[i].name_,
00490           pnh_, "ad/" + ads_[i].name_, 1);
00491     }
00492     digital_input_enable_ = false;
00493     dio_output_default_ = 0;
00494     dio_dir_default_ = 0;
00495     dios_.resize(dio_num_);
00496     for (int i = 0; i < dio_num_; i++)
00497     {
00498       DioParams param;
00499       pnh_.param(std::string("dio") + std::to_string(i) + std::string("_enable"),
00500                  param.enable_, false);
00501       if (param.enable_)
00502       {
00503         pnh_.param(std::string("dio") + std::to_string(i) + std::string("_name"),
00504                    param.name_, std::string(std::string("dio") + std::to_string(i)));
00505 
00506         pnh_.param(std::string("dio") + std::to_string(i) + std::string("_output"),
00507                    param.output_, true);
00508         pnh_.param(std::string("dio") + std::to_string(i) + std::string("_input"),
00509                    param.input_, false);
00510 
00511         if (param.output_)
00512         {
00513           subs_[param.name_] = compat::subscribe<ypspur_ros::DigitalOutput>(
00514               nh_, param.name_,
00515               pnh_, param.name_, 1,
00516               boost::bind(&YpspurRosNode::cbDigitalOutput, this, _1, i));
00517         }
00518 
00519         std::string output_default;
00520         pnh_.param(std::string("dio") + std::to_string(i) + std::string("_default"),
00521                    output_default, std::string("HIGH_IMPEDANCE"));
00522         if (output_default.compare("HIGH_IMPEDANCE") == 0)
00523         {
00524         }
00525         else if (output_default.compare("LOW") == 0)
00526         {
00527           dio_dir_default_ |= 1 << i;
00528         }
00529         else if (output_default.compare("HIGH") == 0)
00530         {
00531           dio_dir_default_ |= 1 << i;
00532           dio_output_default_ |= 1 << i;
00533         }
00534         else if (output_default.compare("PULL_UP") == 0)
00535         {
00536           dio_output_default_ |= 1 << i;
00537         }
00538         else if (output_default.compare("PULL_DOWN") == 0)
00539         {
00540           ROS_ERROR("Digital IO pull down is not supported on this system");
00541         }
00542         if (param.input_)
00543           digital_input_enable_ = true;
00544       }
00545       dios_[i] = param;
00546     }
00547     dio_output_ = dio_output_default_;
00548     dio_dir_ = dio_dir_default_;
00549     if (digital_input_enable_)
00550     {
00551       pubs_["din"] = compat::advertise<ypspur_ros::DigitalInput>(
00552           nh_, "digital_input",
00553           pnh_, "digital_input", 2);
00554     }
00555 
00556     pnh_.param("odom_id", frames_["odom"], std::string("odom"));
00557     pnh_.param("base_link_id", frames_["base_link"], std::string("base_link"));
00558     pnh_.param("origin_id", frames_["origin"], std::string(""));
00559     pnh_.param("hz", params_["hz"], 200.0);
00560 
00561     std::string mode_name;
00562     pnh_.param("OdometryMode", mode_name, std::string("diff"));
00563     if (mode_name.compare("diff") == 0)
00564     {
00565       mode_ = DIFF;
00566       pubs_["wrench"] = compat::advertise<geometry_msgs::WrenchStamped>(
00567           nh_, "wrench",
00568           pnh_, "wrench", 1);
00569       pubs_["odom"] = compat::advertise<nav_msgs::Odometry>(
00570           nh_, "odom",
00571           pnh_, "odom", 1);
00572       subs_["cmd_vel"] = compat::subscribe(
00573           nh_, "cmd_vel",
00574           pnh_, "cmd_vel", 1, &YpspurRosNode::cbCmdVel, this);
00575     }
00576     else if (mode_name.compare("none") == 0)
00577     {
00578     }
00579     else
00580     {
00581       throw(std::runtime_error("unknown mode: " + mode_name));
00582     }
00583 
00584     int max_joint_id;
00585     bool separated_joint;
00586     pnh_.param("max_joint_id", max_joint_id, 32);
00587     pnh_.param("separated_joint_control", separated_joint, false);
00588     int num = 0;
00589     for (int i = 0; i < max_joint_id; i++)
00590     {
00591       std::string name;
00592       name = std::string("joint") + std::to_string(i);
00593       if (pnh_.hasParam(name + std::string("_enable")))
00594       {
00595         bool en;
00596         pnh_.param(name + std::string("_enable"), en, false);
00597         if (en)
00598         {
00599           JointParams jp;
00600           jp.id_ = i;
00601           pnh_.param(name + std::string("_name"), jp.name_, name);
00602           pnh_.param(name + std::string("_accel"), jp.accel_, 3.14);
00603           joint_name_to_num_[jp.name_] = num;
00604           joints_.push_back(jp);
00605           // printf("%s %d %d", jp.name_.c_str(), jp.id_, joint_name_to_num_[jp.name_]);
00606           if (separated_joint)
00607           {
00608             subs_[jp.name_ + std::string("_setVel")] = compat::subscribe<std_msgs::Float32>(
00609                 nh_, jp.name_ + std::string("/set_vel"),
00610                 pnh_, jp.name_ + std::string("_setVel"), 1,
00611                 boost::bind(&YpspurRosNode::cbSetVel, this, _1, num));
00612             subs_[jp.name_ + std::string("_setAccel")] = compat::subscribe<std_msgs::Float32>(
00613                 nh_, jp.name_ + std::string("/set_accel"),
00614                 pnh_, jp.name_ + std::string("_setAccel"), 1,
00615                 boost::bind(&YpspurRosNode::cbSetAccel, this, _1, num));
00616             subs_[jp.name_ + std::string("_vel")] = compat::subscribe<std_msgs::Float32>(
00617                 nh_, jp.name_ + std::string("/vel"),
00618                 pnh_, jp.name_ + std::string("_vel"), 1,
00619                 boost::bind(&YpspurRosNode::cbVel, this, _1, num));
00620             subs_[jp.name_ + std::string("_pos")] = compat::subscribe<std_msgs::Float32>(
00621                 nh_, jp.name_ + std::string("/pos"),
00622                 pnh_, jp.name_ + std::string("_pos"), 1,
00623                 boost::bind(&YpspurRosNode::cbAngle, this, _1, num));
00624           }
00625           subs_[std::string("joint_position")] = compat::subscribe(
00626               nh_, std::string("joint_position"),
00627               pnh_, std::string("joint_position"), 1, &YpspurRosNode::cbJointPosition, this);
00628           num++;
00629         }
00630       }
00631     }
00632 #if !(YPSPUR_JOINT_SUPPORT)
00633     if (joints_.size() != 0)
00634     {
00635       if (!(joints_.size() == 2 && joints_[0].id_ == 0 && joints_[1].id_ == 1))
00636       {
00637         throw(std::runtime_error("This version of yp-spur only supports [joint0_enable: true, joint1_enable: true]"));
00638       }
00639     }
00640 #endif
00641     if (joints_.size() > 0)
00642     {
00643       pubs_["joint"] = compat::advertise<sensor_msgs::JointState>(
00644           nh_, "joint_states",
00645           pnh_, "joint", 2);
00646       subs_["joint"] = compat::subscribe(
00647           nh_, "joint_trajectory",
00648           pnh_, "cmd_joint", joints_.size() * 2, &YpspurRosNode::cbJoint, this);
00649     }
00650     subs_["control_mode"] = compat::subscribe(
00651         nh_, "control_mode",
00652         pnh_, "control_mode", 1, &YpspurRosNode::cbControlMode, this);
00653     control_mode_ = ypspur_ros::ControlMode::VELOCITY;
00654 
00655     pubs_["diag"] = nh_.advertise<diagnostic_msgs::DiagnosticArray>(
00656         "/diagnostics", 1);
00657 
00658     pid_ = 0;
00659     for (int i = 0; i < 2; i++)
00660     {
00661       if (i > 0 || YP::YPSpur_initex(key_) < 0)
00662       {
00663         std::vector<std::string> args =
00664             {
00665               ypspur_bin_,
00666               "-d", port_,
00667               "--admask", ad_mask,
00668               "--msq-key", std::to_string(key_)
00669             };
00670         if (digital_input_enable_)
00671           args.push_back(std::string("--enable-get-digital-io"));
00672         if (simulate_)
00673           args.push_back(std::string("--without-device"));
00674         if (param_file_.size() > 0)
00675         {
00676           args.push_back(std::string("-p"));
00677           args.push_back(param_file_);
00678         }
00679 
00680         char **argv = new char *[args.size() + 1];
00681         for (unsigned int i = 0; i < args.size(); i++)
00682         {
00683           argv[i] = new char[args[i].size() + 1];
00684           memcpy(argv[i], args[i].c_str(), args[i].size());
00685           argv[i][args[i].size()] = 0;
00686         }
00687         argv[args.size()] = nullptr;
00688 
00689         int msq = msgget(key_, 0666 | IPC_CREAT);
00690         msgctl(msq, IPC_RMID, nullptr);
00691 
00692         ROS_WARN("launching ypspur-coordinator");
00693         pid_ = fork();
00694         if (pid_ == -1)
00695         {
00696           const int err = errno;
00697           throw(std::runtime_error(std::string("failed to fork process: ") + strerror(err)));
00698         }
00699         else if (pid_ == 0)
00700         {
00701           execvp(ypspur_bin_.c_str(), argv);
00702           throw(std::runtime_error("failed to start ypspur-coordinator"));
00703         }
00704 
00705         for (unsigned int i = 0; i < args.size(); i++)
00706           delete argv[i];
00707         delete argv;
00708 
00709         for (int i = 4; i >= 0; i--)
00710         {
00711           int status;
00712           if (waitpid(pid_, &status, WNOHANG) == pid_)
00713           {
00714             throw(std::runtime_error("ypspur-coordinator dead immediately"));
00715           }
00716           else if (i == 0)
00717           {
00718             throw(std::runtime_error("failed to init libypspur"));
00719           }
00720           ros::WallDuration(1).sleep();
00721           if (YP::YPSpur_initex(key_) >= 0)
00722             break;
00723         }
00724       }
00725       double ret;
00726       boost::atomic<bool> done(false);
00727       auto get_vel_thread = [&ret, &done]
00728       {
00729         double test_v, test_w;
00730         ret = YP::YPSpur_get_vel(&test_v, &test_w);
00731         done = true;
00732       };
00733       boost::thread spur_test = boost::thread(get_vel_thread);
00734       ros::WallDuration(0.1).sleep();
00735       if (!done)
00736       {
00737         // There is no way to kill thread safely in C++11
00738         // So, just leave it detached.
00739         spur_test.detach();
00740         ROS_WARN("ypspur-coordinator seems to be down - launching");
00741         continue;
00742       }
00743       spur_test.join();
00744       if (ret < 0)
00745       {
00746         ROS_WARN("ypspur-coordinator returns error - launching");
00747         continue;
00748       }
00749       ROS_WARN("ypspur-coordinator launched");
00750       break;
00751     }
00752 
00753     ROS_INFO("ypspur-coordinator conneceted");
00754     signal(SIGINT, sigintHandler);
00755 
00756     YP::YP_get_parameter(YP::YP_PARAM_MAX_VEL, &params_["vel"]);
00757     YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_V, &params_["acc"]);
00758     YP::YP_get_parameter(YP::YP_PARAM_MAX_W, &params_["angvel"]);
00759     YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_W, &params_["angacc"]);
00760 
00761     if (!pnh_.hasParam("vel"))
00762       ROS_WARN("default \"vel\" %0.3f used", (float)params_["vel"]);
00763     if (!pnh_.hasParam("acc"))
00764       ROS_WARN("default \"acc\" %0.3f used", (float)params_["acc"]);
00765     if (!pnh_.hasParam("angvel"))
00766       ROS_WARN("default \"angvel\" %0.3f used", (float)params_["angvel"]);
00767     if (!pnh_.hasParam("angacc"))
00768       ROS_WARN("default \"angacc\" %0.3f used", (float)params_["angacc"]);
00769 
00770     pnh_.param("vel", params_["vel"], params_["vel"]);
00771     pnh_.param("acc", params_["acc"], params_["acc"]);
00772     pnh_.param("angvel", params_["angvel"], params_["angvel"]);
00773     pnh_.param("angacc", params_["angacc"], params_["angacc"]);
00774 
00775     YP::YPSpur_set_vel(params_["vel"]);
00776     YP::YPSpur_set_accel(params_["acc"]);
00777     YP::YPSpur_set_angvel(params_["angvel"]);
00778     YP::YPSpur_set_angaccel(params_["angacc"]);
00779 
00780     YP::YP_set_io_data(dio_output_);
00781     YP::YP_set_io_dir(dio_dir_);
00782   }
00783   ~YpspurRosNode()
00784   {
00785     if (pid_ > 0)
00786     {
00787       ROS_INFO("killing ypspur-coordinator (%d)", (int)pid_);
00788       kill(pid_, SIGINT);
00789       int status;
00790       waitpid(pid_, &status, 0);
00791       ROS_INFO("ypspur-coordinator is killed (status: %d)", status);
00792     }
00793     ros::shutdown();
00794   }
00795   void spin()
00796   {
00797     geometry_msgs::TransformStamped odom_trans;
00798     odom_trans.header.frame_id = frames_["odom"];
00799     odom_trans.child_frame_id = frames_["base_link"];
00800 
00801     nav_msgs::Odometry odom;
00802     geometry_msgs::WrenchStamped wrench;
00803     odom.header.frame_id = frames_["odom"];
00804     odom.child_frame_id = frames_["base_link"];
00805     wrench.header.frame_id = frames_["base_link"];
00806 
00807     odom.pose.pose.position.x = 0;
00808     odom.pose.pose.position.y = 0;
00809     odom.pose.pose.position.z = 0;
00810     odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(0);
00811     odom.twist.twist.linear.x = 0;
00812     odom.twist.twist.linear.y = 0;
00813     odom.twist.twist.angular.z = 0;
00814 
00815     std::map<int, geometry_msgs::TransformStamped> joint_trans;
00816     sensor_msgs::JointState joint;
00817     if (joints_.size() > 0)
00818     {
00819       joint.header.frame_id = std::string("");
00820       joint.velocity.resize(joints_.size());
00821       joint.position.resize(joints_.size());
00822       joint.effort.resize(joints_.size());
00823       for (auto &j : joints_)
00824         joint.name.push_back(j.name_);
00825 
00826       for (unsigned int i = 0; i < joints_.size(); i++)
00827       {
00828         joint_trans[i].header.frame_id = joints_[i].name_ + std::string("_in");
00829         joint_trans[i].child_frame_id = joints_[i].name_ + std::string("_out");
00830         joint.velocity[i] = 0;
00831         joint.position[i] = 0;
00832         joint.effort[i] = 0;
00833       }
00834     }
00835 
00836     ROS_INFO("ypspur_ros main loop started");
00837     ros::Rate loop(params_["hz"]);
00838     while (!g_shutdown)
00839     {
00840       const auto now = ros::Time::now();
00841       const float dt = 1.0 / params_["hz"];
00842 
00843       if (cmd_vel_ && cmd_vel_expire_ > ros::Duration(0))
00844       {
00845         if (cmd_vel_time_ + cmd_vel_expire_ < now)
00846         {
00847           // cmd_vel is too old and expired
00848           cmd_vel_ = nullptr;
00849           if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
00850             YP::YPSpur_vel(0.0, 0.0);
00851         }
00852       }
00853 
00854       if (mode_ == DIFF)
00855       {
00856         double x, y, yaw, v(0), w(0);
00857         double t;
00858 
00859         if (!simulate_control_)
00860         {
00861           t = YP::YPSpur_get_pos(YP::CS_BS, &x, &y, &yaw);
00862           if (t == 0.0)
00863             t = now.toSec();
00864           YP::YPSpur_get_vel(&v, &w);
00865         }
00866         else
00867         {
00868           t = ros::Time::now().toSec();
00869           if (cmd_vel_)
00870           {
00871             v = cmd_vel_->linear.x;
00872             w = cmd_vel_->angular.z;
00873           }
00874           yaw = tf::getYaw(odom.pose.pose.orientation) + dt * w;
00875           x = odom.pose.pose.position.x + dt * v * cosf(yaw);
00876           y = odom.pose.pose.position.y + dt * v * sinf(yaw);
00877         }
00878 
00879         odom.header.stamp = ros::Time(t);
00880         odom.pose.pose.position.x = x;
00881         odom.pose.pose.position.y = y;
00882         odom.pose.pose.position.z = 0;
00883         odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
00884         odom.twist.twist.linear.x = v;
00885         odom.twist.twist.linear.y = 0;
00886         odom.twist.twist.angular.z = w;
00887         pubs_["odom"].publish(odom);
00888 
00889         odom_trans.header.stamp = ros::Time(t) + ros::Duration(tf_time_offset_);
00890         odom_trans.transform.translation.x = x;
00891         odom_trans.transform.translation.y = y;
00892         odom_trans.transform.translation.z = 0;
00893         odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(yaw);
00894         tf_broadcaster_.sendTransform(odom_trans);
00895 
00896         t = YP::YPSpur_get_force(&wrench.wrench.force.x, &wrench.wrench.torque.z);
00897         if (t == 0.0)
00898           t = now.toSec();
00899         wrench.header.stamp = ros::Time(t);
00900         wrench.wrench.force.y = 0;
00901         wrench.wrench.force.z = 0;
00902         wrench.wrench.torque.x = 0;
00903         wrench.wrench.torque.y = 0;
00904         pubs_["wrench"].publish(wrench);
00905 
00906         if (frames_["origin"].length() > 0)
00907         {
00908           try
00909           {
00910             tf::StampedTransform transform;
00911             tf_listener_.lookupTransform(
00912                 frames_["origin"], frames_["base_link"],
00913                 ros::Time(0), transform);
00914 
00915             tfScalar yaw, pitch, roll;
00916             transform.getBasis().getEulerYPR(yaw, pitch, roll);
00917             YP::YPSpur_adjust_pos(YP::CS_GL, transform.getOrigin().x(),
00918                                   transform.getOrigin().y(),
00919                                   yaw);
00920           }
00921           catch (tf::TransformException ex)
00922           {
00923             ROS_ERROR("Failed to feedback localization result to YP-Spur (%s)", ex.what());
00924           }
00925         }
00926       }
00927       if (joints_.size() > 0)
00928       {
00929         double t;
00930         if (!simulate_control_)
00931         {
00932 #if !(YPSPUR_JOINT_SUPPORT)
00933           while (1)
00934           {
00935             double js[2];
00936             int i;
00937             t = YP::YP_get_wheel_ang(&js[0], &js[1]);
00938             i = 0;
00939             for (auto &j : joints_)
00940               joint.position[i++] = js[j.id_];
00941             if (t != YP::YP_get_wheel_vel(&js[0], &js[1]))
00942               continue;
00943             i = 0;
00944             for (auto &j : joints_)
00945               joint.velocity[i++] = js[j.id_];
00946             if (t != YP::YP_get_wheel_torque(&js[0], &js[1]))
00947               continue;
00948             i = 0;
00949             for (auto &j : joints_)
00950               joint.effort[i++] = js[j.id_];
00951 
00952             if (t == 0.0)
00953               t = ros::Time::now().toSec();
00954             break;
00955           }
00956 #else
00957           t = -1.0;
00958           while (t < 0.0)
00959           {
00960             int i = 0;
00961             for (auto &j : joints_)
00962             {
00963               const double t0 = YP::YP_get_joint_ang(j.id_, &joint.position[i]);
00964               const double t1 = YP::YP_get_joint_vel(j.id_, &joint.velocity[i]);
00965               const double t2 = YP::YP_get_joint_torque(j.id_, &joint.effort[i]);
00966 
00967               if (t0 != t1 || t1 != t2)
00968               {
00969                 // Retry if updated during this joint
00970                 t = -1.0;
00971                 break;
00972               }
00973               if (t < 0.0)
00974               {
00975                 t = t0;
00976               }
00977               else if (t != t0)
00978               {
00979                 // Retry if updated during loops
00980                 t = -1.0;
00981                 break;
00982               }
00983               i++;
00984             }
00985             if (t == 0.0)
00986               t = ros::Time::now().toSec();
00987           }
00988 #endif
00989           joint.header.stamp = ros::Time(t);
00990         }
00991         else
00992         {
00993           t = ros::Time::now().toSec();
00994           for (unsigned int i = 0; i < joints_.size(); i++)
00995           {
00996             auto vel_prev = joint.velocity[i];
00997             switch (joints_[i].control_)
00998             {
00999               case JointParams::STOP:
01000                 break;
01001               case JointParams::TRAJECTORY:
01002               case JointParams::POSITION:
01003               case JointParams::VELOCITY:
01004                 switch (joints_[i].control_)
01005                 {
01006                   case JointParams::POSITION:
01007                   {
01008                     float position_err = joints_[i].angle_ref_ - joint.position[i];
01009                     joints_[i].vel_ref_ = sqrtf(2.0 * joints_[i].accel_ * fabs(position_err));
01010                     if (joints_[i].vel_ref_ > joints_[i].vel_)
01011                       joints_[i].vel_ref_ = joints_[i].vel_;
01012                     if (position_err < 0)
01013                       joints_[i].vel_ref_ = -joints_[i].vel_ref_;
01014                   }
01015                   break;
01016                   case JointParams::TRAJECTORY:
01017                   {
01018                     float position_err = joints_[i].angle_ref_ - joint.position[i];
01019                     float v_sq = joints_[i].vel_end_ * joints_[i].vel_end_ + 2.0 * joints_[i].accel_ * position_err;
01020                     joints_[i].vel_ref_ = sqrtf(fabs(v_sq));
01021 
01022                     float vel_max;
01023                     if (fabs(joints_[i].vel_) < fabs(joints_[i].vel_end_))
01024                     {
01025                       if (fabs(position_err) <
01026                           (joints_[i].vel_end_ * joints_[i].vel_end_ - joints_[i].vel_ * joints_[i].vel_) /
01027                               (2.0 * joints_[i].accel_))
01028                         vel_max = fabs(joints_[i].vel_end_);
01029                       else
01030                         vel_max = joints_[i].vel_;
01031                     }
01032                     else
01033                       vel_max = joints_[i].vel_;
01034 
01035                     if (joints_[i].vel_ref_ > vel_max)
01036                       joints_[i].vel_ref_ = vel_max;
01037                     if (position_err < 0)
01038                       joints_[i].vel_ref_ = -joints_[i].vel_ref_;
01039                   }
01040                   break;
01041                   default:
01042                     break;
01043                 }
01044                 joint.velocity[i] = joints_[i].vel_ref_;
01045                 if (joint.velocity[i] < vel_prev - dt * joints_[i].accel_)
01046                 {
01047                   joint.velocity[i] = vel_prev - dt * joints_[i].accel_;
01048                 }
01049                 else if (joint.velocity[i] > vel_prev + dt * joints_[i].accel_)
01050                 {
01051                   joint.velocity[i] = vel_prev + dt * joints_[i].accel_;
01052                 }
01053                 joint.position[i] += joint.velocity[i] * dt;
01054                 break;
01055             }
01056           }
01057           joint.header.stamp = ros::Time(t);
01058         }
01059         pubs_["joint"].publish(joint);
01060 
01061         for (unsigned int i = 0; i < joints_.size(); i++)
01062         {
01063           joint_trans[i].transform.rotation =
01064               tf::createQuaternionMsgFromYaw(joint.position[i]);
01065           joint_trans[i].header.stamp = ros::Time(t) + ros::Duration(tf_time_offset_);
01066           tf_broadcaster_.sendTransform(joint_trans[i]);
01067         }
01068 
01069 #if (YPSPUR_JOINT_ANG_VEL_SUPPORT)
01070         for (unsigned int jid = 0; jid < joints_.size(); jid++)
01071         {
01072           if (joints_[jid].control_ != JointParams::TRAJECTORY)
01073             continue;
01074 
01075           auto &cmd_joint_ = joints_[jid].cmd_joint_;
01076           auto t = now - cmd_joint_.header.stamp;
01077           if (t < ros::Duration(0))
01078             continue;
01079 
01080           bool done = true;
01081           for (auto &cmd : cmd_joint_.points)
01082           {
01083             if (cmd.time_from_start < ros::Duration(0))
01084               continue;
01085             if (now > cmd_joint_.header.stamp + cmd.time_from_start)
01086               continue;
01087             done = false;
01088 
01089             double ang_err = cmd.positions[0] - joint.position[jid];
01090             double &vel_end_ = cmd.velocities[0];
01091             double &vel_start = joint.velocity[jid];
01092             auto t_left = cmd.time_from_start - t;
01093 
01094             double v;
01095             double v_min;
01096             bool v_found = true;
01097             while (true)
01098             {
01099               // ROS_INFO("st: %0.3f, en: %0.3f, err: %0.3f, t: %0.3f",
01100               //          vel_start, vel_end_, ang_err, t_left.toSec());
01101               int s;
01102               if (vel_end_ > vel_start)
01103                 s = 1;
01104               else
01105                 s = -1;
01106               v = (s * (vel_start + vel_end_) * (vel_start - vel_end_) +
01107                    ang_err * joints_[jid].accel_ * 2.0) /
01108                   (2.0 * s * (vel_start - vel_end_) + joints_[jid].accel_ * 2.0 * (t_left.toSec()));
01109 
01110               double err_deacc;
01111               err_deacc = fabs(vel_end_ * vel_end_ - v * v) / (joints_[jid].accel_ * 2.0);
01112               // ROS_INFO("v+-: %0.3f", v);
01113               v_min = fabs(v);
01114               if ((vel_start * s <= v * s || err_deacc >= fabs(ang_err)) &&
01115                   v * s <= vel_end_ * s)
01116                 break;
01117 
01118               v_min = DBL_MAX;
01119 
01120               auto vf = [](const double &st, const double &en,
01121                            const double &acc, const double &err, const double &t,
01122                            const int &sig, const int &sol, double &ret)
01123               {
01124                 double sq;
01125                 sq = -4.0 * st * st +
01126                      8.0 * st * en -
01127                      4.0 * en * en +
01128                      4.0 * sig * acc * 2 * (t * (st + en) - 2.0 * err) +
01129                      4.0 * acc * acc * t * t;
01130                 if (sq < 0)
01131                   return false;
01132 
01133                 ret = (2.0 * sig * (st + en) + 2.0 * acc * t + sol * sqrt(sq)) / (4.0 * sig);
01134 
01135                 return true;
01136               };
01137 
01138               v_found = false;
01139 
01140               if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
01141                      1, 1, v))
01142               {
01143                 // ROS_INFO("v++: sol+ %0.3f", v);
01144                 if (v >= vel_start && v >= vel_end_)
01145                 {
01146                   if (v_min > fabs(v))
01147                     v_min = fabs(v);
01148                   v_found = true;
01149                 }
01150               }
01151               if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
01152                      -1, 1, v))
01153               {
01154                 // ROS_INFO("v--: sol+ %0.3f", v);
01155                 if (v <= vel_start && v <= vel_end_)
01156                 {
01157                   if (v_min > fabs(v))
01158                     v_min = fabs(v);
01159                   v_found = true;
01160                 }
01161               }
01162               if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
01163                      1, -1, v))
01164               {
01165                 // ROS_INFO("v++: sol- %0.3f", v);
01166                 if (v >= vel_start && v >= vel_end_)
01167                 {
01168                   if (v_min > fabs(v))
01169                     v_min = fabs(v);
01170                   v_found = true;
01171                 }
01172               }
01173               if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
01174                      -1, -1, v))
01175               {
01176                 // ROS_INFO("v--: sol- %0.3f", v);
01177                 if (v <= vel_start && v <= vel_end_)
01178                 {
01179                   if (v_min > fabs(v))
01180                     v_min = fabs(v);
01181                   v_found = true;
01182                 }
01183               }
01184               break;
01185             }
01186             if (v_found)
01187             {
01188               // ROS_INFO("v: %0.3f", v_min);
01189               joints_[jid].angle_ref_ = cmd.positions[0];
01190               joints_[jid].vel_end_ = vel_end_;
01191               joints_[jid].vel_ = v_min;
01192 
01193               YP::YP_set_joint_vel(joints_[jid].id_, v_min);
01194               YP::YP_set_joint_accel(joints_[jid].id_, joints_[jid].accel_);
01195               YP::YP_joint_ang_vel(joints_[jid].id_, cmd.positions[0], vel_end_);
01196             }
01197             else
01198             {
01199               ROS_ERROR("Impossible trajectory given");
01200             }
01201             break;
01202           }
01203 
01204           if (done)
01205           {
01206             if ((joints_[jid].vel_end_ > 0.0 &&
01207                  joints_[jid].angle_ref_ > joint.position[jid] &&
01208                  joints_[jid].angle_ref_ < joint.position[jid] + joints_[jid].vel_ref_ * dt) ||
01209                 (joints_[jid].vel_end_ < 0.0 &&
01210                  joints_[jid].angle_ref_ < joint.position[jid] &&
01211                  joints_[jid].angle_ref_ > joint.position[jid] + joints_[jid].vel_ref_ * dt))
01212             {
01213               joints_[jid].control_ = JointParams::VELOCITY;
01214               joints_[jid].vel_ref_ = joints_[jid].vel_end_;
01215             }
01216           }
01217         }
01218 #endif
01219       }
01220 
01221       for (int i = 0; i < ad_num_; i++)
01222       {
01223         if (ads_[i].enable_)
01224         {
01225           std_msgs::Float32 ad;
01226           ad.data = YP::YP_get_ad_value(i) * ads_[i].gain_ + ads_[i].offset_;
01227           pubs_["ad/" + ads_[i].name_].publish(ad);
01228         }
01229       }
01230 
01231       if (digital_input_enable_)
01232       {
01233         ypspur_ros::DigitalInput din;
01234 
01235         din.header.stamp = ros::Time::now();
01236         int in = YP::YP_get_ad_value(15);
01237         for (int i = 0; i < dio_num_; i++)
01238         {
01239           if (!dios_[i].enable_)
01240             continue;
01241           din.name.push_back(dios_[i].name_);
01242           if (in & (1 << i))
01243             din.state.push_back(true);
01244           else
01245             din.state.push_back(false);
01246         }
01247         pubs_["din"].publish(din);
01248       }
01249 
01250       for (int i = 0; i < dio_num_; i++)
01251       {
01252         if (dio_revert_[i] != ros::Time(0))
01253         {
01254           if (dio_revert_[i] < now)
01255           {
01256             revertDigitalOutput(i);
01257           }
01258         }
01259       }
01260       updateDiagnostics(now);
01261 
01262       if (YP::YP_get_error_state())
01263       {
01264         ROS_ERROR("ypspur-coordinator is not active");
01265         break;
01266       }
01267       ros::spinOnce();
01268       loop.sleep();
01269 
01270       int status;
01271       if (waitpid(pid_, &status, WNOHANG) == pid_)
01272       {
01273         if (WIFEXITED(status))
01274         {
01275           ROS_ERROR("ypspur-coordinator exited");
01276         }
01277         else
01278         {
01279           if (WIFSTOPPED(status))
01280           {
01281             ROS_ERROR("ypspur-coordinator dead with signal %d",
01282                       WSTOPSIG(status));
01283           }
01284           else
01285           {
01286             ROS_ERROR("ypspur-coordinator dead");
01287           }
01288           updateDiagnostics(now, true);
01289         }
01290         break;
01291       }
01292     }
01293     ROS_INFO("ypspur_ros main loop terminated");
01294   }
01295 };
01296 
01297 int main(int argc, char *argv[])
01298 {
01299   ros::init(argc, argv, "ypspur_ros");
01300 
01301   try
01302   {
01303     YpspurRosNode yr;
01304     yr.spin();
01305   }
01306   catch (std::runtime_error &e)
01307   {
01308     ROS_ERROR("%s", e.what());
01309     return -1;
01310   }
01311 
01312   return 0;
01313 }


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:19:02