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> 53 #include <sys/types.h> 56 #include <boost/atomic.hpp> 57 #include <boost/chrono.hpp> 58 #include <boost/thread.hpp> 59 #include <boost/thread/future.hpp> 84 std::map<std::string, ros::Publisher>
pubs_;
85 std::map<std::string, ros::Subscriber>
subs_;
92 std::map<std::string, std::string>
frames_;
150 const int ad_num_ = 8;
155 const int dio_num_ = 8;
170 control_mode_ = msg->vehicle_control_mode;
171 switch (control_mode_)
173 case ypspur_ros::ControlMode::OPEN:
176 case ypspur_ros::ControlMode::TORQUE:
179 case ypspur_ros::ControlMode::VELOCITY:
183 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr &msg)
187 if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
189 YP::YPSpur_vel(msg->linear.x, msg->angular.z);
192 void cbJoint(
const trajectory_msgs::JointTrajectory::ConstPtr &msg)
194 #if !(YPSPUR_JOINT_ANG_VEL_SUPPORT) 195 ROS_ERROR(
"JointTrajectory command is not available on this YP-Spur version");
199 std_msgs::Header
header = msg->header;
203 std::map<std::string, trajectory_msgs::JointTrajectory> new_cmd_joints;
205 for (
const std::string &name : msg->joint_names)
207 trajectory_msgs::JointTrajectory cmd_joint;
208 cmd_joint.header = header;
209 cmd_joint.joint_names.resize(1);
210 cmd_joint.joint_names[0] = name;
211 cmd_joint.points.clear();
213 for (
auto &cmd : msg->points)
215 if (header.stamp + cmd.time_from_start < now)
218 "Ignored outdated JointTrajectory command " 219 "(joint: %s, now: %0.6lf, stamp: %0.6lf, time_from_start: %0.6lf)",
220 name.c_str(), now.
toSec(), header.stamp.toSec(), cmd.time_from_start.toSec());
224 trajectory_msgs::JointTrajectoryPoint
p;
225 p.time_from_start = cmd.time_from_start;
226 p.positions.resize(1);
227 p.velocities.resize(1);
228 if (cmd.velocities.size() <= i)
229 p.velocities[0] = 0.0;
231 p.velocities[0] = cmd.velocities[i];
232 p.positions[0] = cmd.positions[i];
234 cmd_joint.points.push_back(p);
238 if (cmd_joint.points.size() != msg->points.size())
241 new_cmd_joints[name] = cmd_joint;
244 for (
auto &new_cmd_joint : new_cmd_joints)
246 const int joint_num = joint_name_to_num_[new_cmd_joint.first];
247 joints_[joint_num].control_ = JointParams::TRAJECTORY;
248 joints_[joint_num].cmd_joint_ = new_cmd_joint.second;
251 void cbSetVel(
const std_msgs::Float32::ConstPtr &msg,
int num)
254 joints_[num].vel_ = msg->data;
255 #if !(YPSPUR_JOINT_SUPPORT) 256 YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
258 YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
261 void cbSetAccel(
const std_msgs::Float32::ConstPtr &msg,
int num)
264 joints_[num].accel_ = msg->data;
265 #if !(YPSPUR_JOINT_SUPPORT) 266 YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
268 YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
271 void cbVel(
const std_msgs::Float32::ConstPtr &msg,
int num)
274 joints_[num].vel_ref_ = msg->data;
275 joints_[num].control_ = JointParams::VELOCITY;
276 #if !(YPSPUR_JOINT_SUPPORT) 277 YP::YP_wheel_vel(joints_[0].vel_ref_, joints_[1].vel_ref_);
279 YP::YP_joint_vel(joints_[num].id_, joints_[num].vel_ref_);
282 void cbAngle(
const std_msgs::Float32::ConstPtr &msg,
int num)
284 joints_[num].angle_ref_ = msg->data;
285 joints_[num].control_ = JointParams::POSITION;
286 #if !(YPSPUR_JOINT_SUPPORT) 287 YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
289 YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
295 for (
auto &name : msg->joint_names)
297 if (joint_name_to_num_.find(name) == joint_name_to_num_.end())
299 ROS_ERROR(
"Unknown joint name '%s'", name.c_str());
302 int num = joint_name_to_num_[name];
304 joints_[num].vel_ = msg->velocities[i];
305 joints_[num].accel_ = msg->accelerations[i];
306 joints_[num].angle_ref_ = msg->positions[i];
307 joints_[num].control_ = JointParams::POSITION;
309 #if (YPSPUR_JOINT_SUPPORT) 310 YP::YP_set_joint_vel(joints_[num].id_, joints_[num].vel_);
311 YP::YP_set_joint_accel(joints_[num].id_, joints_[num].accel_);
312 YP::YP_joint_ang(joints_[num].id_, joints_[num].angle_ref_);
316 #if !(YPSPUR_JOINT_SUPPORT) 317 YP::YP_set_wheel_vel(joints_[0].vel_, joints_[1].vel_);
318 YP::YP_set_wheel_accel(joints_[0].accel_, joints_[1].accel_);
319 YP::YP_wheel_ang(joints_[0].angle_ref_, joints_[1].angle_ref_);
325 const auto dio_output_prev = dio_output_;
326 const auto dio_dir_prev = dio_dir_;
327 const unsigned int mask = 1 << id_;
331 case ypspur_ros::DigitalOutput::HIGH_IMPEDANCE:
332 dio_output_ &= ~mask;
335 case ypspur_ros::DigitalOutput::LOW:
336 dio_output_ &= ~mask;
339 case ypspur_ros::DigitalOutput::HIGH:
343 case ypspur_ros::DigitalOutput::PULL_UP:
347 case ypspur_ros::DigitalOutput::PULL_DOWN:
348 ROS_ERROR(
"Digital IO pull down is not supported on this system");
351 if (dio_output_ != dio_output_prev)
352 YP::YP_set_io_data(dio_output_);
353 if (dio_dir_ != dio_dir_prev)
354 YP::YP_set_io_dir(dio_dir_);
363 const auto dio_output_prev = dio_output_;
364 const auto dio_dir_prev = dio_dir_;
365 const unsigned int mask = 1 << id_;
367 dio_output_ &= ~mask;
368 dio_output_ |= dio_output_default_ & mask;
370 dio_dir_ |= dio_output_default_ & mask;
372 if (dio_output_ != dio_output_prev)
373 YP::YP_set_io_data(dio_output_);
374 if (dio_dir_ != dio_dir_prev)
375 YP::YP_set_io_dir(dio_dir_);
381 const int connection_error = connection_down ? 1 : YP::YP_get_error_state();
384 #if (YPSPUR_GET_DEVICE_ERROR_STATE_SUPPORT) 386 if (!connection_error)
387 t = YP::YP_get_device_error_state(0, &err);
388 device_error_state_ |= err;
391 "This version of yp-spur doesn't provide device error status. " 392 "Consider building ypspur_ros with latest yp-spur.");
394 if (device_error_state_time_ +
ros::Duration(1.0) < now || connection_down ||
395 device_error_state_ != device_error_state_prev_)
397 device_error_state_time_ = now;
398 device_error_state_prev_ = device_error_state_;
400 diagnostic_msgs::DiagnosticArray msg;
401 msg.header.stamp = now;
402 msg.status.resize(1);
403 msg.status[0].name =
"YP-Spur Motor Controller";
404 msg.status[0].hardware_id =
"ipc-key" + std::to_string(key_);
405 if (device_error_state_ == 0 && connection_error == 0)
409 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
410 msg.status[0].message =
"Motor controller doesn't " 411 "provide device error state.";
417 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
418 msg.status[0].message =
"Motor controller doesn't " 419 "update latest device error state.";
423 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::OK;
424 msg.status[0].message =
"Motor controller is running without error.";
430 msg.status[0].level = diagnostic_msgs::DiagnosticStatus::ERROR;
431 if (connection_error)
432 msg.status[0].message +=
433 "Connection to ypspur-coordinator is down.";
434 if (device_error_state_)
435 msg.status[0].message +=
436 std::string((msg.status[0].message.size() > 0 ?
" " :
"")) +
437 "Motor controller reported error id " +
438 std::to_string(device_error_state_) +
".";
440 msg.status[0].values.resize(2);
441 msg.status[0].values[0].key =
"connection_error";
442 msg.status[0].values[0].value = std::to_string(connection_error);
443 msg.status[0].values[1].key =
"device_error";
444 msg.status[0].values[1].value = std::to_string(device_error_state_);
446 pubs_[
"diag"].publish(msg);
447 device_error_state_ = 0;
455 , device_error_state_(0)
456 , device_error_state_prev_(0)
457 , device_error_state_time_(0)
461 pnh_.
param(
"port", port_, std::string(
"/dev/ttyACM0"));
462 pnh_.
param(
"ipc_key", key_, 28741);
463 pnh_.
param(
"simulate", simulate_,
false);
464 pnh_.
param(
"simulate_control", simulate_control_,
false);
465 if (simulate_control_)
467 pnh_.
param(
"ypspur_bin", ypspur_bin_, std::string(
"ypspur-coordinator"));
468 pnh_.
param(
"param_file", param_file_, std::string(
""));
469 pnh_.
param(
"tf_time_offset", tf_time_offset_, 0.0);
471 double cmd_vel_expire_s;
472 pnh_.
param(
"cmd_vel_expire", cmd_vel_expire_s, -1.0);
475 std::string ad_mask(
"");
476 ads_.resize(ad_num_);
477 for (
int i = 0; i < ad_num_; i++)
479 pnh_.
param(std::string(
"ad") + std::to_string(i) + std::string(
"_enable"),
480 ads_[i].enable_,
false);
481 pnh_.
param(std::string(
"ad") + std::to_string(i) + std::string(
"_name"),
482 ads_[i].name_, std::string(
"ad") + std::to_string(i));
483 pnh_.
param(std::string(
"ad") + std::to_string(i) + std::string(
"_gain"),
485 pnh_.
param(std::string(
"ad") + std::to_string(i) + std::string(
"_offset"),
486 ads_[i].offset_, 0.0);
487 ad_mask = (ads_[i].enable_ ? std::string(
"1") : std::string(
"0")) + ad_mask;
488 pubs_[
"ad/" + ads_[i].name_] = compat::advertise<std_msgs::Float32>(
489 nh_,
"ad/" + ads_[i].name_,
490 pnh_,
"ad/" + ads_[i].name_, 1);
492 digital_input_enable_ =
false;
493 dio_output_default_ = 0;
494 dio_dir_default_ = 0;
495 dios_.resize(dio_num_);
496 for (
int i = 0; i < dio_num_; i++)
499 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_enable"),
503 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_name"),
504 param.
name_, std::string(std::string(
"dio") + std::to_string(i)));
506 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_output"),
508 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_input"),
513 subs_[param.
name_] = compat::subscribe<ypspur_ros::DigitalOutput>(
515 pnh_, param.
name_, 1,
519 std::string output_default;
520 pnh_.
param(std::string(
"dio") + std::to_string(i) + std::string(
"_default"),
521 output_default, std::string(
"HIGH_IMPEDANCE"));
522 if (output_default.compare(
"HIGH_IMPEDANCE") == 0)
525 else if (output_default.compare(
"LOW") == 0)
527 dio_dir_default_ |= 1 << i;
529 else if (output_default.compare(
"HIGH") == 0)
531 dio_dir_default_ |= 1 << i;
532 dio_output_default_ |= 1 << i;
534 else if (output_default.compare(
"PULL_UP") == 0)
536 dio_output_default_ |= 1 << i;
538 else if (output_default.compare(
"PULL_DOWN") == 0)
540 ROS_ERROR(
"Digital IO pull down is not supported on this system");
543 digital_input_enable_ =
true;
547 dio_output_ = dio_output_default_;
548 dio_dir_ = dio_dir_default_;
549 if (digital_input_enable_)
551 pubs_[
"din"] = compat::advertise<ypspur_ros::DigitalInput>(
552 nh_,
"digital_input",
553 pnh_,
"digital_input", 2);
556 pnh_.
param(
"odom_id", frames_[
"odom"], std::string(
"odom"));
557 pnh_.
param(
"base_link_id", frames_[
"base_link"], std::string(
"base_link"));
558 pnh_.
param(
"origin_id", frames_[
"origin"], std::string(
""));
559 pnh_.
param(
"hz", params_[
"hz"], 200.0);
561 std::string mode_name;
562 pnh_.
param(
"OdometryMode", mode_name, std::string(
"diff"));
563 if (mode_name.compare(
"diff") == 0)
566 pubs_[
"wrench"] = compat::advertise<geometry_msgs::WrenchStamped>(
569 pubs_[
"odom"] = compat::advertise<nav_msgs::Odometry>(
576 else if (mode_name.compare(
"none") == 0)
581 throw(std::runtime_error(
"unknown mode: " + mode_name));
585 bool separated_joint;
586 pnh_.
param(
"max_joint_id", max_joint_id, 32);
587 pnh_.
param(
"separated_joint_control", separated_joint,
false);
589 for (
int i = 0; i < max_joint_id; i++)
592 name = std::string(
"joint") + std::to_string(i);
593 if (pnh_.
hasParam(name + std::string(
"_enable")))
596 pnh_.
param(name + std::string(
"_enable"), en,
false);
601 pnh_.
param(name + std::string(
"_name"), jp.
name_, name);
602 pnh_.
param(name + std::string(
"_accel"), jp.
accel_, 3.14);
603 joint_name_to_num_[jp.
name_] = num;
604 joints_.push_back(jp);
608 subs_[jp.
name_ + std::string(
"_setVel")] = compat::subscribe<std_msgs::Float32>(
609 nh_, jp.
name_ + std::string(
"/set_vel"),
610 pnh_, jp.
name_ + std::string(
"_setVel"), 1,
612 subs_[jp.
name_ + std::string(
"_setAccel")] = compat::subscribe<std_msgs::Float32>(
613 nh_, jp.
name_ + std::string(
"/set_accel"),
614 pnh_, jp.
name_ + std::string(
"_setAccel"), 1,
616 subs_[jp.
name_ + std::string(
"_vel")] = compat::subscribe<std_msgs::Float32>(
617 nh_, jp.
name_ + std::string(
"/vel"),
618 pnh_, jp.
name_ + std::string(
"_vel"), 1,
620 subs_[jp.
name_ + std::string(
"_pos")] = compat::subscribe<std_msgs::Float32>(
621 nh_, jp.
name_ + std::string(
"/pos"),
622 pnh_, jp.
name_ + std::string(
"_pos"), 1,
626 nh_, std::string(
"joint_position"),
632 #if !(YPSPUR_JOINT_SUPPORT) 633 if (joints_.size() != 0)
635 if (!(joints_.size() == 2 && joints_[0].id_ == 0 && joints_[1].id_ == 1))
637 throw(std::runtime_error(
"This version of yp-spur only supports [joint0_enable: true, joint1_enable: true]"));
641 if (joints_.size() > 0)
643 pubs_[
"joint"] = compat::advertise<sensor_msgs::JointState>(
647 nh_,
"joint_trajectory",
653 control_mode_ = ypspur_ros::ControlMode::VELOCITY;
655 pubs_[
"diag"] = nh_.
advertise<diagnostic_msgs::DiagnosticArray>(
659 for (
int i = 0; i < 2; i++)
661 if (i > 0 || YP::YPSpur_initex(key_) < 0)
663 std::vector<std::string>
args =
668 "--msq-key", std::to_string(key_)
670 if (digital_input_enable_)
671 args.push_back(std::string(
"--enable-get-digital-io"));
673 args.push_back(std::string(
"--without-device"));
674 if (param_file_.size() > 0)
676 args.push_back(std::string(
"-p"));
677 args.push_back(param_file_);
680 char **argv =
new char *[args.size() + 1];
681 for (
unsigned int i = 0; i < args.size(); i++)
683 argv[i] =
new char[args[i].size() + 1];
684 memcpy(argv[i], args[i].c_str(), args[i].size());
685 argv[i][args[i].size()] = 0;
687 argv[args.size()] =
nullptr;
689 int msq = msgget(key_, 0666 | IPC_CREAT);
690 msgctl(msq, IPC_RMID,
nullptr);
692 ROS_WARN(
"launching ypspur-coordinator");
696 const int err = errno;
697 throw(std::runtime_error(std::string(
"failed to fork process: ") + strerror(err)));
701 execvp(ypspur_bin_.c_str(), argv);
702 throw(std::runtime_error(
"failed to start ypspur-coordinator"));
705 for (
unsigned int i = 0; i < args.size(); i++)
709 for (
int i = 4; i >= 0; i--)
712 if (waitpid(pid_, &status, WNOHANG) == pid_)
714 throw(std::runtime_error(
"ypspur-coordinator dead immediately"));
718 throw(std::runtime_error(
"failed to init libypspur"));
721 if (YP::YPSpur_initex(key_) >= 0)
726 boost::atomic<bool> done(
false);
727 auto get_vel_thread = [&ret, &done]
729 double test_v, test_w;
730 ret = YP::YPSpur_get_vel(&test_v, &test_w);
733 boost::thread spur_test = boost::thread(get_vel_thread);
740 ROS_WARN(
"ypspur-coordinator seems to be down - launching");
746 ROS_WARN(
"ypspur-coordinator returns error - launching");
749 ROS_WARN(
"ypspur-coordinator launched");
753 ROS_INFO(
"ypspur-coordinator conneceted");
756 YP::YP_get_parameter(YP::YP_PARAM_MAX_VEL, ¶ms_[
"vel"]);
757 YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_V, ¶ms_[
"acc"]);
758 YP::YP_get_parameter(YP::YP_PARAM_MAX_W, ¶ms_[
"angvel"]);
759 YP::YP_get_parameter(YP::YP_PARAM_MAX_ACC_W, ¶ms_[
"angacc"]);
762 ROS_WARN(
"default \"vel\" %0.3f used", (
float)params_[
"vel"]);
764 ROS_WARN(
"default \"acc\" %0.3f used", (
float)params_[
"acc"]);
766 ROS_WARN(
"default \"angvel\" %0.3f used", (
float)params_[
"angvel"]);
768 ROS_WARN(
"default \"angacc\" %0.3f used", (
float)params_[
"angacc"]);
770 pnh_.
param(
"vel", params_[
"vel"], params_[
"vel"]);
771 pnh_.
param(
"acc", params_[
"acc"], params_[
"acc"]);
772 pnh_.
param(
"angvel", params_[
"angvel"], params_[
"angvel"]);
773 pnh_.
param(
"angacc", params_[
"angacc"], params_[
"angacc"]);
775 YP::YPSpur_set_vel(params_[
"vel"]);
776 YP::YPSpur_set_accel(params_[
"acc"]);
777 YP::YPSpur_set_angvel(params_[
"angvel"]);
778 YP::YPSpur_set_angaccel(params_[
"angacc"]);
780 YP::YP_set_io_data(dio_output_);
781 YP::YP_set_io_dir(dio_dir_);
787 ROS_INFO(
"killing ypspur-coordinator (%d)", (
int)pid_);
790 waitpid(pid_, &status, 0);
791 ROS_INFO(
"ypspur-coordinator is killed (status: %d)", status);
797 geometry_msgs::TransformStamped odom_trans;
798 odom_trans.header.frame_id = frames_[
"odom"];
799 odom_trans.child_frame_id = frames_[
"base_link"];
801 nav_msgs::Odometry odom;
802 geometry_msgs::WrenchStamped wrench;
803 odom.header.frame_id = frames_[
"odom"];
804 odom.child_frame_id = frames_[
"base_link"];
805 wrench.header.frame_id = frames_[
"base_link"];
807 odom.pose.pose.position.x = 0;
808 odom.pose.pose.position.y = 0;
809 odom.pose.pose.position.z = 0;
811 odom.twist.twist.linear.x = 0;
812 odom.twist.twist.linear.y = 0;
813 odom.twist.twist.angular.z = 0;
815 std::map<int, geometry_msgs::TransformStamped> joint_trans;
816 sensor_msgs::JointState joint;
817 if (joints_.size() > 0)
819 joint.header.frame_id = std::string(
"");
820 joint.velocity.resize(joints_.size());
821 joint.position.resize(joints_.size());
822 joint.effort.resize(joints_.size());
823 for (
auto &j : joints_)
824 joint.name.push_back(j.name_);
826 for (
unsigned int i = 0; i < joints_.size(); i++)
828 joint_trans[i].header.frame_id = joints_[i].name_ + std::string(
"_in");
829 joint_trans[i].child_frame_id = joints_[i].name_ + std::string(
"_out");
830 joint.velocity[i] = 0;
831 joint.position[i] = 0;
836 ROS_INFO(
"ypspur_ros main loop started");
841 const float dt = 1.0 / params_[
"hz"];
845 if (cmd_vel_time_ + cmd_vel_expire_ < now)
849 if (control_mode_ == ypspur_ros::ControlMode::VELOCITY)
850 YP::YPSpur_vel(0.0, 0.0);
856 double x,
y, yaw, v(0),
w(0);
859 if (!simulate_control_)
861 t = YP::YPSpur_get_pos(YP::CS_BS, &x, &y, &yaw);
864 YP::YPSpur_get_vel(&v, &w);
871 v = cmd_vel_->linear.x;
872 w = cmd_vel_->angular.z;
874 yaw =
tf::getYaw(odom.pose.pose.orientation) + dt * w;
875 x = odom.pose.pose.position.x + dt * v * cosf(yaw);
876 y = odom.pose.pose.position.y + dt * v * sinf(yaw);
880 odom.pose.pose.position.x = x;
881 odom.pose.pose.position.y = y;
882 odom.pose.pose.position.z = 0;
884 odom.twist.twist.linear.x = v;
885 odom.twist.twist.linear.y = 0;
886 odom.twist.twist.angular.z = w;
887 pubs_[
"odom"].publish(odom);
890 odom_trans.transform.translation.x = x;
891 odom_trans.transform.translation.y = y;
892 odom_trans.transform.translation.z = 0;
896 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);
906 if (frames_[
"origin"].
length() > 0)
912 frames_[
"origin"], frames_[
"base_link"],
917 YP::YPSpur_adjust_pos(YP::CS_GL, transform.
getOrigin().
x(),
923 ROS_ERROR(
"Failed to feedback localization result to YP-Spur (%s)", ex.what());
927 if (joints_.size() > 0)
930 if (!simulate_control_)
932 #if !(YPSPUR_JOINT_SUPPORT) 937 t = YP::YP_get_wheel_ang(&js[0], &js[1]);
939 for (
auto &j : joints_)
940 joint.position[i++] = js[j.id_];
941 if (t != YP::YP_get_wheel_vel(&js[0], &js[1]))
944 for (
auto &j : joints_)
945 joint.velocity[i++] = js[j.id_];
946 if (t != YP::YP_get_wheel_torque(&js[0], &js[1]))
949 for (
auto &j : joints_)
950 joint.effort[i++] = js[j.id_];
961 for (
auto &j : joints_)
963 const double t0 = YP::YP_get_joint_ang(j.id_, &joint.position[i]);
964 const double t1 = YP::YP_get_joint_vel(j.id_, &joint.velocity[i]);
965 const double t2 = YP::YP_get_joint_torque(j.id_, &joint.effort[i]);
967 if (t0 != t1 || t1 != t2)
994 for (
unsigned int i = 0; i < joints_.size(); i++)
996 auto vel_prev = joint.velocity[i];
997 switch (joints_[i].control_)
999 case JointParams::STOP:
1001 case JointParams::TRAJECTORY:
1002 case JointParams::POSITION:
1003 case JointParams::VELOCITY:
1004 switch (joints_[i].control_)
1006 case JointParams::POSITION:
1008 float position_err = joints_[i].angle_ref_ - joint.position[i];
1009 joints_[i].vel_ref_ = sqrtf(2.0 * joints_[i].accel_ * fabs(position_err));
1010 if (joints_[i].vel_ref_ > joints_[i].vel_)
1011 joints_[i].vel_ref_ = joints_[i].vel_;
1012 if (position_err < 0)
1013 joints_[i].vel_ref_ = -joints_[i].vel_ref_;
1016 case JointParams::TRAJECTORY:
1018 float position_err = joints_[i].angle_ref_ - joint.position[i];
1019 float v_sq = joints_[i].vel_end_ * joints_[i].vel_end_ + 2.0 * joints_[i].accel_ * position_err;
1020 joints_[i].vel_ref_ = sqrtf(fabs(v_sq));
1023 if (fabs(joints_[i].vel_) < fabs(joints_[i].vel_end_))
1025 if (fabs(position_err) <
1026 (joints_[i].vel_end_ * joints_[i].vel_end_ - joints_[i].vel_ * joints_[i].vel_) /
1027 (2.0 * joints_[i].accel_))
1028 vel_max = fabs(joints_[i].vel_end_);
1030 vel_max = joints_[i].vel_;
1033 vel_max = joints_[i].vel_;
1035 if (joints_[i].vel_ref_ > vel_max)
1036 joints_[i].vel_ref_ = vel_max;
1037 if (position_err < 0)
1038 joints_[i].vel_ref_ = -joints_[i].vel_ref_;
1044 joint.velocity[i] = joints_[i].vel_ref_;
1045 if (joint.velocity[i] < vel_prev - dt * joints_[i].accel_)
1047 joint.velocity[i] = vel_prev - dt * joints_[i].accel_;
1049 else if (joint.velocity[i] > vel_prev + dt * joints_[i].accel_)
1051 joint.velocity[i] = vel_prev + dt * joints_[i].accel_;
1053 joint.position[i] += joint.velocity[i] * dt;
1059 pubs_[
"joint"].publish(joint);
1061 for (
unsigned int i = 0; i < joints_.size(); i++)
1063 joint_trans[i].transform.rotation =
1069 #if (YPSPUR_JOINT_ANG_VEL_SUPPORT) 1070 for (
unsigned int jid = 0; jid < joints_.size(); jid++)
1072 if (joints_[jid].control_ != JointParams::TRAJECTORY)
1075 auto &cmd_joint_ = joints_[jid].cmd_joint_;
1076 auto t = now - cmd_joint_.header.stamp;
1081 for (
auto &cmd : cmd_joint_.points)
1085 if (now > cmd_joint_.header.stamp + cmd.time_from_start)
1089 double ang_err = cmd.positions[0] - joint.position[jid];
1090 double &vel_end_ = cmd.velocities[0];
1091 double &vel_start = joint.velocity[jid];
1092 auto t_left = cmd.time_from_start - t;
1096 bool v_found =
true;
1102 if (vel_end_ > vel_start)
1106 v = (s * (vel_start + vel_end_) * (vel_start - vel_end_) +
1107 ang_err * joints_[jid].accel_ * 2.0) /
1108 (2.0 * s * (vel_start - vel_end_) + joints_[jid].accel_ * 2.0 * (t_left.toSec()));
1111 err_deacc = fabs(vel_end_ * vel_end_ - v * v) / (joints_[jid].accel_ * 2.0);
1114 if ((vel_start * s <= v * s || err_deacc >= fabs(ang_err)) &&
1115 v * s <= vel_end_ * s)
1120 auto vf = [](
const double &st,
const double &en,
1121 const double &acc,
const double &err,
const double &t,
1122 const int &sig,
const int &sol,
double &ret)
1125 sq = -4.0 * st * st +
1128 4.0 * sig * acc * 2 * (t * (st + en) - 2.0 * err) +
1129 4.0 * acc * acc * t * t;
1133 ret = (2.0 * sig * (st + en) + 2.0 * acc * t + sol * sqrt(sq)) / (4.0 * sig);
1140 if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1144 if (v >= vel_start && v >= vel_end_)
1146 if (v_min > fabs(v))
1151 if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1155 if (v <= vel_start && v <= vel_end_)
1157 if (v_min > fabs(v))
1162 if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1166 if (v >= vel_start && v >= vel_end_)
1168 if (v_min > fabs(v))
1173 if (vf(vel_start, vel_end_, joints_[jid].accel_, ang_err, t_left.toSec(),
1177 if (v <= vel_start && v <= vel_end_)
1179 if (v_min > fabs(v))
1189 joints_[jid].angle_ref_ = cmd.positions[0];
1190 joints_[jid].vel_end_ = vel_end_;
1191 joints_[jid].vel_ = v_min;
1193 YP::YP_set_joint_vel(joints_[jid].id_, v_min);
1194 YP::YP_set_joint_accel(joints_[jid].id_, joints_[jid].accel_);
1195 YP::YP_joint_ang_vel(joints_[jid].id_, cmd.positions[0], vel_end_);
1199 ROS_ERROR(
"Impossible trajectory given");
1206 if ((joints_[jid].vel_end_ > 0.0 &&
1207 joints_[jid].angle_ref_ > joint.position[jid] &&
1208 joints_[jid].angle_ref_ < joint.position[jid] + joints_[jid].vel_ref_ * dt) ||
1209 (joints_[jid].vel_end_ < 0.0 &&
1210 joints_[jid].angle_ref_ < joint.position[jid] &&
1211 joints_[jid].angle_ref_ > joint.position[jid] + joints_[jid].vel_ref_ * dt))
1213 joints_[jid].control_ = JointParams::VELOCITY;
1214 joints_[jid].vel_ref_ = joints_[jid].vel_end_;
1221 for (
int i = 0; i < ad_num_; i++)
1223 if (ads_[i].enable_)
1225 std_msgs::Float32
ad;
1226 ad.data = YP::YP_get_ad_value(i) * ads_[i].gain_ + ads_[i].offset_;
1227 pubs_[
"ad/" + ads_[i].name_].publish(ad);
1231 if (digital_input_enable_)
1233 ypspur_ros::DigitalInput din;
1236 int in = YP::YP_get_ad_value(15);
1237 for (
int i = 0; i < dio_num_; i++)
1239 if (!dios_[i].enable_)
1241 din.name.push_back(dios_[i].name_);
1243 din.state.push_back(
true);
1245 din.state.push_back(
false);
1247 pubs_[
"din"].publish(din);
1250 for (
int i = 0; i < dio_num_; i++)
1254 if (dio_revert_[i] < now)
1256 revertDigitalOutput(i);
1260 updateDiagnostics(now);
1262 if (YP::YP_get_error_state())
1264 ROS_ERROR(
"ypspur-coordinator is not active");
1271 if (waitpid(pid_, &status, WNOHANG) == pid_)
1273 if (WIFEXITED(status))
1279 if (WIFSTOPPED(status))
1281 ROS_ERROR(
"ypspur-coordinator dead with signal %d",
1288 updateDiagnostics(now,
true);
1293 ROS_INFO(
"ypspur_ros main loop terminated");
1306 catch (std::runtime_error &e)
int main(int argc, char *argv[])
std::map< std::string, int > joint_name_to_num_
void cbVel(const std_msgs::Float32::ConstPtr &msg, int num)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
tf::TransformBroadcaster tf_broadcaster_
void cbJointPosition(const ypspur_ros::JointPositionControl::ConstPtr &msg)
std::vector< AdParams > ads_
void updateDiagnostics(const ros::Time &now, const bool connection_down=false)
std::map< std::string, double > params_
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
void sigintHandler(int sig)
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
static double getYaw(const Quaternion &bt_q)
std::map< int, ros::Time > dio_revert_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< DioParams > dios_
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
trajectory_msgs::JointTrajectory cmd_joint_
std::vector< JointParams > joints_
void cbControlMode(const ypspur_ros::ControlMode::ConstPtr &msg)
void cbAngle(const std_msgs::Float32::ConstPtr &msg, int num)
#define ROS_WARN_ONCE(...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool digital_input_enable_
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::map< std::string, std::string > frames_
unsigned int dio_output_default_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cbSetVel(const std_msgs::Float32::ConstPtr &msg, int num)
std::map< std::string, ros::Publisher > pubs_
tf::TransformListener tf_listener_
ros::Duration cmd_vel_expire_
TFSIMD_FORCE_INLINE const tfScalar & w() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
unsigned int dio_dir_default_
ros::Time device_error_state_time_
void cbJoint(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void cbSetAccel(const std_msgs::Float32::ConstPtr &msg, int num)
ROSCPP_DECL void shutdown()
double p(YPSpur_param id, enum motor_id motor)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
bool hasParam(const std::string &key) const
int device_error_state_prev_
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())
ROSCPP_DECL void spinOnce()
void cbDigitalOutput(const ypspur_ros::DigitalOutput::ConstPtr &msg, int id_)
geometry_msgs::Twist::ConstPtr cmd_vel_
std::map< std::string, ros::Subscriber > subs_
void revertDigitalOutput(int id_)