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>
55 #include <sys/types.h>
58 #include <boost/atomic.hpp>
59 #include <boost/chrono.hpp>
60 #include <boost/thread.hpp>
61 #include <boost/thread/future.hpp>
86 std::map<std::string, ros::Publisher>
pubs_;
87 std::map<std::string, ros::Subscriber>
subs_;
96 std::map<std::string, std::string>
frames_;
183 case ypspur_ros::ControlMode::OPEN:
186 case ypspur_ros::ControlMode::TORQUE:
189 case ypspur_ros::ControlMode::VELOCITY:
193 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
199 YP::YPSpur_vel(msg->linear.x, msg->angular.z);
202 void cbJoint(
const trajectory_msgs::JointTrajectory::ConstPtr& msg)
206 std_msgs::Header
header = msg->header;
210 std::map<std::string, trajectory_msgs::JointTrajectory> new_cmd_joints;
212 for (
const std::string& name : msg->joint_names)
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();
220 for (
auto& cmd : msg->points)
222 if (
header.stamp + cmd.time_from_start < now)
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());
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;
238 p.velocities[0] = cmd.velocities[i];
239 p.positions[0] = cmd.positions[i];
241 cmd_joint.points.push_back(
p);
245 if (cmd_joint.points.size() != msg->points.size())
248 new_cmd_joints[name] = cmd_joint;
251 for (
auto& new_cmd_joint : new_cmd_joints)
255 joints_[joint_num].cmd_joint_ = new_cmd_joint.second;
258 void cbSetVel(
const std_msgs::Float32::ConstPtr& msg,
int num)
264 void cbSetAccel(
const std_msgs::Float32::ConstPtr& msg,
int num)
267 joints_[num].accel_ = msg->data;
270 void cbVel(
const std_msgs::Float32::ConstPtr& msg,
int num)
273 joints_[num].vel_ref_ = msg->data;
277 void cbAngle(
const std_msgs::Float32::ConstPtr& msg,
int num)
279 joints_[num].angle_ref_ = msg->data;
286 for (
auto& name : msg->joint_names)
290 ROS_ERROR(
"Unknown joint name '%s'", name.c_str());
295 joints_[num].vel_ = msg->velocities[i];
296 joints_[num].accel_ = msg->accelerations[i];
297 joints_[num].angle_ref_ = msg->positions[i];
311 const unsigned int mask = 1 << id_;
315 case ypspur_ros::DigitalOutput::HIGH_IMPEDANCE:
319 case ypspur_ros::DigitalOutput::LOW:
323 case ypspur_ros::DigitalOutput::HIGH:
327 case ypspur_ros::DigitalOutput::PULL_UP:
331 case ypspur_ros::DigitalOutput::PULL_DOWN:
332 ROS_ERROR(
"Digital IO pull down is not supported on this system");
349 const unsigned int mask = 1 << id_;
365 const int connection_error = connection_down ? 1 : YP::YP_get_error_state();
369 if (!connection_error)
370 t = YP::YP_get_device_error_state(0, &err);
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_);
388 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
389 msg.status[0].message =
"Motor controller doesn't "
390 "provide device error state.";
396 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
397 msg.status[0].message =
"Motor controller doesn't "
398 "update latest device error state.";
402 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
403 msg.status[0].message =
"Motor controller is running without error.";
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 " +
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";
425 pubs_[
"diag"].publish(msg);
455 double cmd_vel_expire_s;
456 pnh_.
param(
"cmd_vel_expire", cmd_vel_expire_s, -1.0);
459 std::string ad_mask(
"");
461 for (
int i = 0; i <
ad_num_; i++)
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"),
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>(
483 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_enable"),
484 param.enable_,
false);
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)));
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);
497 subs_[
param.name_] = compat::subscribe<ypspur_ros::DigitalOutput>(
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)
509 else if (output_default.compare(
"LOW") == 0)
513 else if (output_default.compare(
"HIGH") == 0)
518 else if (output_default.compare(
"PULL_UP") == 0)
522 else if (output_default.compare(
"PULL_DOWN") == 0)
524 ROS_ERROR(
"Digital IO pull down is not supported on this system");
535 pubs_[
"din"] = compat::advertise<ypspur_ros::DigitalInput>(
536 nh_,
"digital_input",
537 pnh_,
"digital_input", 2);
545 std::string mode_name;
546 pnh_.
param(
"OdometryMode", mode_name, std::string(
"diff"));
547 if (mode_name.compare(
"diff") == 0)
550 pubs_[
"wrench"] = compat::advertise<geometry_msgs::WrenchStamped>(
553 pubs_[
"odom"] = compat::advertise<nav_msgs::Odometry>(
564 else if (mode_name.compare(
"none") == 0)
569 throw(std::runtime_error(
"unknown mode: " + mode_name));
573 bool separated_joint;
574 pnh_.
param(
"max_joint_id", max_joint_id, 32);
575 pnh_.
param(
"separated_joint_control", separated_joint,
false);
577 for (
int i = 0; i < max_joint_id; i++)
580 name = std::string(
"joint") + std::to_string(i);
584 pnh_.
param(name + std::string(
"_enable"), en,
false);
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,
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,
604 subs_[jp.
name_ + std::string(
"_vel")] = compat::subscribe<std_msgs::Float32>(
605 nh_, jp.
name_ + std::string(
"/vel"),
608 subs_[jp.
name_ + std::string(
"_pos")] = compat::subscribe<std_msgs::Float32>(
609 nh_, jp.
name_ + std::string(
"/pos"),
614 nh_, std::string(
"joint_position"),
622 pubs_[
"joint"] = compat::advertise<sensor_msgs::JointState>(
626 nh_,
"joint_trajectory",
638 for (
int i = 0; i < 2; i++)
640 if (i > 0 || YP::YPSpur_initex(
key_) < 0)
642 std::vector<std::string> args =
647 "--msq-key", std::to_string(
key_)
650 args.push_back(std::string(
"--enable-get-digital-io"));
652 args.push_back(std::string(
"--without-device"));
655 args.push_back(std::string(
"-p"));
659 char** argv =
new char*[args.size() + 1];
660 for (
unsigned int i = 0; i < args.size(); i++)
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;
666 argv[args.size()] =
nullptr;
668 int msq = msgget(
key_, 0666 | IPC_CREAT);
669 msgctl(msq, IPC_RMID,
nullptr);
671 ROS_WARN(
"launching ypspur-coordinator");
675 const int err = errno;
676 throw(std::runtime_error(std::string(
"failed to fork process: ") + strerror(err)));
681 throw(std::runtime_error(
"failed to start ypspur-coordinator"));
684 for (
unsigned int i = 0; i < args.size(); i++)
688 for (
int i = 4; i >= 0; i--)
691 if (waitpid(
pid_, &status, WNOHANG) ==
pid_)
693 if (WIFSIGNALED(status))
695 throw(std::runtime_error(
696 "ypspur-coordinator dead immediately by signal " + std::to_string(WTERMSIG(status))));
698 if (WIFEXITED(status))
700 throw(std::runtime_error(
701 "ypspur-coordinator dead immediately with exit code " + std::to_string(WEXITSTATUS(status))));
703 throw(std::runtime_error(
"ypspur-coordinator dead immediately"));
707 throw(std::runtime_error(
"failed to init libypspur"));
710 if (YP::YPSpur_initex(
key_) >= 0)
715 boost::atomic<bool> done(
false);
716 auto get_vel_thread = [&ret, &done]
718 double test_v, test_w;
719 ret = YP::YPSpur_get_vel(&test_v, &test_w);
722 boost::thread spur_test = boost::thread(get_vel_thread);
729 ROS_WARN(
"ypspur-coordinator seems to be down - launching");
735 ROS_WARN(
"ypspur-coordinator returns error - launching");
738 ROS_WARN(
"ypspur-coordinator launched");
742 ROS_INFO(
"ypspur-coordinator conneceted");
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"]);
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"]);
775 if (
pid_ > 0 && YP::YP_get_error_state() == 0)
780 waitpid(
pid_, &status, 0);
781 ROS_INFO(
"ypspur-coordinator is killed (status: %d)", status);
786 geometry_msgs::TransformStamped odom_trans;
787 odom_trans.header.frame_id =
frames_[
"odom"];
788 odom_trans.child_frame_id =
frames_[
"base_link"];
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"];
796 odom.pose.pose.position.x = 0;
797 odom.pose.pose.position.y = 0;
798 odom.pose.pose.position.z = 0;
800 odom.twist.twist.linear.x = 0;
801 odom.twist.twist.linear.y = 0;
802 odom.twist.twist.angular.z = 0;
804 std::map<int, geometry_msgs::TransformStamped> joint_trans;
805 sensor_msgs::JointState joint;
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());
813 joint.name.push_back(j.name_);
815 for (
unsigned int i = 0; i <
joints_.size(); i++)
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;
825 ROS_INFO(
"ypspur_ros main loop started");
830 const float dt = 1.0 /
params_[
"hz"];
839 YP::YPSpur_vel(0.0, 0.0);
845 double x, y, yaw, v(0), w(0);
850 t = YP::YPSpur_get_pos(YP::CS_BS, &x, &y, &yaw);
853 YP::YPSpur_get_vel(&v, &w);
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);
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;
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);
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;
895 t = YP::YPSpur_get_force(&wrench.wrench.force.x, &wrench.wrench.torque.z);
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);
917 transform.getBasis().getEulerYPR(yaw, pitch, roll);
918 YP::YPSpur_adjust_pos(YP::CS_GL, transform.getOrigin().x(),
919 transform.getOrigin().y(),
924 ROS_ERROR(
"Failed to feedback localization result to YP-Spur (%s)", ex.what());
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]);
943 if (t0 != t1 || t1 != t2)
969 for (
unsigned int i = 0; i <
joints_.size(); i++)
971 auto vel_prev = joint.velocity[i];
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));
987 if (position_err < 0)
993 float position_err =
joints_[i].angle_ref_ - joint.position[i];
995 joints_[i].vel_ref_ = sqrtf(fabs(v_sq));
1000 if (fabs(position_err) <
1003 vel_max = fabs(
joints_[i].vel_end_);
1010 if (
joints_[i].vel_ref_ > vel_max)
1011 joints_[i].vel_ref_ = vel_max;
1012 if (position_err < 0)
1019 joint.velocity[i] =
joints_[i].vel_ref_;
1020 if (joint.velocity[i] < vel_prev - dt *
joints_[i].accel_)
1022 joint.velocity[i] = vel_prev - dt *
joints_[i].accel_;
1024 else if (joint.velocity[i] > vel_prev + dt *
joints_[i].accel_)
1026 joint.velocity[i] = vel_prev + dt *
joints_[i].accel_;
1028 joint.position[i] += joint.velocity[i] * dt;
1037 pubs_[
"joint"].publish(joint);
1042 for (
unsigned int i = 0; i <
joints_.size(); i++)
1049 for (
unsigned int jid = 0; jid <
joints_.size(); jid++)
1054 auto& cmd_joint_ =
joints_[jid].cmd_joint_;
1055 auto t = now - cmd_joint_.header.stamp;
1060 for (
auto& cmd : cmd_joint_.points)
1064 if (now > cmd_joint_.header.stamp + cmd.time_from_start)
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;
1075 bool v_found =
true;
1081 if (vel_end_ > vel_start)
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()));
1090 err_deacc = fabs(vel_end_ * vel_end_ - v * v) / (
joints_[jid].accel_ * 2.0);
1093 if ((vel_start * s <= v * s || err_deacc >= fabs(ang_err)) &&
1094 v *
s <= vel_end_ *
s)
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)
1104 sq = -4.0 * st * st +
1107 4.0 * sig * acc * 2 * (
t * (st + en) - 2.0 * err) +
1108 4.0 * acc * acc *
t *
t;
1112 ret = (2.0 * sig * (st + en) + 2.0 * acc *
t + sol * sqrt(sq)) / (4.0 * sig);
1119 if (vf(vel_start, vel_end_,
joints_[jid].accel_, ang_err, t_left.toSec(),
1123 if (v >= vel_start && v >= vel_end_)
1125 if (v_min > fabs(v))
1130 if (vf(vel_start, vel_end_,
joints_[jid].accel_, ang_err, t_left.toSec(),
1134 if (v <= vel_start && v <= vel_end_)
1136 if (v_min > fabs(v))
1141 if (vf(vel_start, vel_end_,
joints_[jid].accel_, ang_err, t_left.toSec(),
1145 if (v >= vel_start && v >= vel_end_)
1147 if (v_min > fabs(v))
1152 if (vf(vel_start, vel_end_,
joints_[jid].accel_, ang_err, t_left.toSec(),
1156 if (v <= vel_start && v <= vel_end_)
1158 if (v_min > fabs(v))
1168 joints_[jid].angle_ref_ = cmd.positions[0];
1169 joints_[jid].vel_end_ = vel_end_;
1172 YP::YP_set_joint_vel(
joints_[jid].id_, v_min);
1174 YP::YP_joint_ang_vel(
joints_[jid].id_, cmd.positions[0], vel_end_);
1178 ROS_ERROR(
"Impossible trajectory given");
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))
1199 for (
int i = 0; i <
ad_num_; i++)
1201 if (
ads_[i].enable_)
1203 std_msgs::Float32
ad;
1204 ad.data = YP::YP_get_ad_value(i) *
ads_[i].gain_ +
ads_[i].offset_;
1211 ypspur_ros::DigitalInput din;
1214 int in = YP::YP_get_ad_value(15);
1217 if (!
dios_[i].enable_)
1219 din.name.push_back(
dios_[i].name_);
1221 din.state.push_back(
true);
1223 din.state.push_back(
false);
1225 pubs_[
"din"].publish(din);
1240 if (YP::YP_get_error_state())
1247 if (waitpid(
pid_, &status, WNOHANG) ==
pid_)
1249 if (WIFEXITED(status))
1255 if (WIFSTOPPED(status))
1257 ROS_ERROR(
"ypspur-coordinator dead with signal %d",
1269 ROS_INFO(
"ypspur_ros main loop terminated");
1271 if (YP::YP_get_error_state())
1273 ROS_ERROR(
"ypspur-coordinator is not active");
1293 catch (std::runtime_error& e)