seed_r7_robot_hardware.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Yohei Kakiuchi (JSK lab.)
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Open Source Robotics Foundation
18  * nor the names of its contributors may be
19  * used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <thread>
38 
39 
40 namespace robot_hardware
41 {
42 
43  bool RobotHW::init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) // add joint list
44  {
45  std::string port_upper;
46  std::string port_lower;
47 
48  // reading paramerters
49  robot_hw_nh.param<std::string>("port_upper", port_upper, "/dev/aero_upper");
50  robot_hw_nh.param<std::string>("port_lower", port_lower, "/dev/aero_lower");
51  robot_hw_nh.param<std::string>("robot_model_plugin", robot_model_plugin_,
52  "seed_r7_robot_interface/TypeF");
53  //
54  if (robot_hw_nh.hasParam("/joint_settings/upper"))
55  robot_hw_nh.getParam("/joint_settings/upper/joints", joint_names_upper_);
56  else
57  ROS_WARN("/joint_settings/upper read error");
58  //
59  if (robot_hw_nh.hasParam("/joint_settings/lower"))
60  robot_hw_nh.getParam("/joint_settings/lower/joints", joint_names_lower_);
61  else
62  ROS_WARN("/joint_settings/lower read error");
63  //
64  if (robot_hw_nh.hasParam("controller_rate")) {
65  double rate;
66  robot_hw_nh.getParam("controller_rate", rate);
67  CONTROL_PERIOD_US_ = (1000*1000)/rate;
68  } else {
69  CONTROL_PERIOD_US_ = 50*1000; // 50ms
70  }
71  if (robot_hw_nh.hasParam("overlap_scale")) {
72  double scl;
73  robot_hw_nh.getParam("overlap_scale", scl);
74  OVERLAP_SCALE_ = scl;
75  } else {
76  OVERLAP_SCALE_ = 2.8;
77  }
78 
79  ROS_INFO("upper_port: %s", port_upper.c_str());
80  ROS_INFO("lower_port: %s", port_lower.c_str());
81  ROS_INFO("cycle: %f [ms], overlap_scale %f", CONTROL_PERIOD_US_*0.001, OVERLAP_SCALE_);
82 
83  // create controllers
86 
87  // load stroke converter
88  // converter is dependent per robot strucutre, therefore uses plugin
89  stroke_converter_ = converter_loader_.createInstance(robot_model_plugin_);
90  if (!stroke_converter_->initialize(robot_hw_nh)) {
91  ROS_ERROR("Failed to initiate stroke converter");
92  return false;
93  }
94 
96 
98  for (int i = 0; i < number_of_angles_; ++i) {
99  if (i < joint_names_upper_.size()) joint_list_[i] = joint_names_upper_[i];
100  else joint_list_[i] = joint_names_lower_[i - joint_names_upper_.size()];
101  }
102 
103  prev_ref_strokes_.resize(number_of_angles_);
104  initialized_flag_ = false;
105 
106  std::string model_str;
107  if (!root_nh.getParam("robot_description", model_str)) {
108  ROS_ERROR("Failed to get model from robot_description");
109  return false;
110  }
111  urdf::Model model;
112  if (!model.initString(model_str)) {
113  ROS_ERROR("Failed to parse robot_description");
114  return false;
115  }
116 
117  ROS_DEBUG("read %d joints", number_of_angles_);
118  for (int i = 0; i < number_of_angles_; ++i) {
119  ROS_DEBUG(" %d: %s", i, joint_list_[i].c_str());
120  if (!model.getJoint(joint_list_[i])) {
121  ROS_ERROR("Joint %s does not exist in urdf model", joint_list_[i].c_str());
122  return false;
123  }
124  }
125 
126  joint_types_.resize(number_of_angles_);
127  joint_control_methods_.resize(number_of_angles_);
128  joint_position_.resize(number_of_angles_);
129  joint_velocity_.resize(number_of_angles_);
130  joint_effort_.resize(number_of_angles_);
131  joint_position_command_.resize(number_of_angles_);
132  joint_velocity_command_.resize(number_of_angles_);
133  joint_effort_command_.resize(number_of_angles_);
134 
135  readPos(ros::Time::now(), ros::Duration(0.0), true); // initial
136 
137  // Initialize values
138  for (unsigned int j = 0; j < number_of_angles_; ++j) {
139  joint_velocity_[j] = 0.0;
140  joint_velocity_command_[j] = 0.0;
141  joint_effort_[j] = 0.0; // N/m for continuous joints
142  joint_effort_command_[j] = 0.0;
143 
144  std::string jointname = joint_list_[j];
145  // Create joint state interface for all joints
148  (jointname, &joint_position_[j], &joint_velocity_[j], &joint_effort_[j]));
149 
150  joint_control_methods_[j] = ControlMethod::POSITION;
154  pj_interface_.registerHandle(joint_handle);
155 
157  const bool urdf_limits_ok
158  = joint_limits_interface::getJointLimits(model.getJoint(jointname), limits);
159  if (!urdf_limits_ok) {
160  ROS_WARN("urdf limits of joint %s is not defined", jointname.c_str());
161  }
162  // Register handle in joint limits interface (Limits spec)
163  joint_limits_interface::PositionJointSaturationHandle limits_handle(joint_handle,limits);
164  pj_sat_interface_.registerHandle(limits_handle);
165  }
166  // Register interfaces
169 
170  // Battery Voltage Publisher
171  bat_vol_pub_ = robot_hw_nh.advertise<std_msgs::Float32>("voltage", 1);
173 
174  // Get Robot Firmware Version
175  ROS_INFO("Upper Firmware Ver. is [ %s ]", controller_upper_->getFirmwareVersion().c_str() );
176  ROS_INFO("Lower Firmware Ver. is [ %s ]", controller_lower_->getFirmwareVersion().c_str() );
177 
178  //Robot Status
180  = root_nh.advertiseService("reset_robot_status", &RobotHW::resetRobotStatusCallback,this);
182 
183  //robot status view
184  diagnostic_updater_.setHardwareID("SEED-Noid-Mover");
185  diagnostic_updater_.add("RobotStatus",this,&RobotHW::setDiagnostics);
186 
187  return true;
188  }
189 
190  void RobotHW::readPos(const ros::Time& time, const ros::Duration& period, bool update)
191  {
192  mutex_lower_.lock();
193  mutex_upper_.lock();
194  if (update) {
195  std::thread t1([&](){
196  controller_upper_->getPosition();
197  });
198  std::thread t2([&](){
199  controller_lower_->getPosition();
200  });
201  t1.join();
202  t2.join();
203  }
204  mutex_upper_.unlock();
205  mutex_lower_.unlock();
206 
207  // whole body strokes
208  std::vector<int16_t> act_strokes(0);
209  std::vector<int16_t> act_upper_strokes;
210  std::vector<int16_t> act_lower_strokes;
211 
212  //remap
213  controller_upper_->remapAeroToRos(act_upper_strokes, controller_upper_->raw_data_);
214  controller_lower_->remapAeroToRos(act_lower_strokes, controller_lower_->raw_data_);
215 
216  act_strokes.insert(act_strokes.end(),act_upper_strokes.begin(),act_upper_strokes.end());
217  act_strokes.insert(act_strokes.end(),act_lower_strokes.begin(),act_lower_strokes.end());
218 
219  // whole body positions from strokes
220  std::vector<double> act_positions;
221  act_positions.resize(number_of_angles_);
222 
223  // convert from stroke to angle
224  stroke_converter_->Stroke2Angle(act_positions, act_strokes);
225 
226  double tm = period.toSec();
227  for(unsigned int j=0; j < number_of_angles_; j++) {
228  float position = act_positions[j];
229  float velocity = 0.0;
230 
231  joint_position_[j] = position;
232  joint_velocity_[j] = velocity; // read velocity from HW
233  joint_effort_[j] = 0; // read effort from HW
234  }
235 
236  if (!initialized_flag_) {
237  for(unsigned int j = 0; j < number_of_angles_; j++) {
239  ROS_DEBUG("%d: %s - %f", j, joint_list_[j].c_str(), joint_position_command_[j]);
240  }
241  initialized_flag_ = true;
242  }
243 
244  //check robot status flag
245  setRobotStatus();
246 
247  //in case of error flag is high
249  ROS_WARN("The robot is protective stopped, please release it.");
250  }
251  return;
252  }
253 
254  void RobotHW::read(const ros::Time& time, const ros::Duration& period)
255  {
256  return;
257  }
258 
259  void RobotHW::write(const ros::Time& time, const ros::Duration& period)
260  {
262 
264  std::vector<double > ref_positions(number_of_angles_);
265  for (unsigned int j = 0; j < number_of_angles_; ++j) {
266  switch (joint_control_methods_[j]) {
267  case ControlMethod::POSITION:
268  {
269  ref_positions[j] = joint_position_command_[j];
270  }
271  break;
272  case ControlMethod::VELOCITY:
273  {
274  }
275  break;
276  case ControlMethod::EFFORT:
277  {
278  }
279  break;
280  case ControlMethod::POSITION_PID:
281  {
282  }
283  break;
284  case ControlMethod::VELOCITY_PID:
285  {
286  }
287  break;
288  } // switch
289  } // for
290 
291  std::vector<bool > mask_positions(number_of_angles_);
292  std::fill(mask_positions.begin(), mask_positions.end(), true); // send if true
293 
294  // convert from angle to stroke
295  std::vector<int16_t> ref_strokes(ref_positions.size());
296  stroke_converter_->Angle2Stroke(ref_strokes, ref_positions);
297 
298  for (int i = 0; i < number_of_angles_; ++i) {
299  double tmp = ref_strokes[i];
300  if (tmp == prev_ref_strokes_[i]) {
301  mask_positions[i] = false;
302  }
303  prev_ref_strokes_[i] = tmp;
304  }
305 
306  // masking
307  std::vector<int16_t> snt_strokes(ref_strokes);
308  for (size_t i = 0; i < ref_strokes.size() ; ++i) {
309  if (!mask_positions[i]) snt_strokes[i] = 0x7FFF;
310  }
311 
312  // split strokes into upper and lower
313  std::vector<int16_t> upper_strokes;
314  std::vector<int16_t> lower_strokes;
315 
316  // remap
317  if (controller_upper_->is_open_) controller_upper_->remapRosToAero(upper_strokes,snt_strokes);
318  else controller_upper_->remapRosToAero(upper_strokes,ref_strokes);
319  if (controller_lower_->is_open_) controller_lower_->remapRosToAero(lower_strokes,snt_strokes);
320  else controller_lower_->remapRosToAero(lower_strokes,ref_strokes);
321 
322  uint16_t time_csec = static_cast<uint16_t>((OVERLAP_SCALE_ * CONTROL_PERIOD_US_)/(1000*10));
323 
324  mutex_lower_.lock();
325  mutex_upper_.lock();
326  {
327  std::thread t1([&](){
328  controller_upper_->sendPosition(time_csec, upper_strokes);
329  });
330  std::thread t2([&](){
331  controller_lower_->sendPosition(time_csec, lower_strokes);
332  });
333  t1.join();
334  t2.join();
335  }
336  mutex_upper_.unlock();
337  mutex_lower_.unlock();
338 
339  // read
340  readPos(time, period, false);
341  return;
342  }
343 
345 // specific functions are below: ///
347  void RobotHW::runHandScript(uint8_t _number, uint16_t _script, uint8_t _current)
348  {
349  mutex_upper_.lock();
350  if(_script == 2){
351  controller_upper_->runScript(_number, 4);
352  usleep(20 * 1000); //magic number
353  controller_upper_->setCurrent(_number, _current, _current);
354  }
355  controller_upper_->runScript(_number, _script);
356  ROS_INFO("sendnum : %d, script : %d", _number, _script);
357  mutex_upper_.unlock();
358  }
359 
360  void RobotHW::turnWheel(std::vector<int16_t> &_vel)
361  {
362  mutex_lower_.lock();
363  controller_lower_->sendVelocity(_vel);
364  mutex_lower_.unlock();
365  }
366 
367  void RobotHW::onWheelServo(bool _value)
368  {
369  mutex_lower_.lock();
370  controller_lower_->onServo(_value);
371  mutex_lower_.unlock();
372  }
373 
375  {
376  // max voltage is 26[V]
377  // min voltage is 22.2[V]
378  std_msgs::Float32 voltage;
379  mutex_lower_.lock();
380  voltage.data = controller_lower_->getBatteryVoltage();
381  mutex_lower_.unlock();
382  bat_vol_pub_.publish(voltage);
383  }
384 
385  void RobotHW::runLedScript(uint8_t _number, uint16_t _script)
386  {
387  mutex_lower_.lock();
388  controller_lower_->runScript(_number, _script);
389  mutex_lower_.unlock();
390  }
391 
393  {
394  comm_err_ = controller_lower_->comm_err_ || controller_upper_->comm_err_;
395 
396  robot_status_.connection_err_ = controller_lower_->robot_status_.connection_err_ ||
397  controller_upper_->robot_status_.connection_err_;
398 
399  robot_status_.calib_err_ = controller_lower_->robot_status_.calib_err_ ||
400  controller_upper_->robot_status_.calib_err_;
401 
402  robot_status_.motor_err_ = controller_lower_->robot_status_.motor_err_ ||
403  controller_upper_->robot_status_.motor_err_;
404 
405  robot_status_.temp_err_ = controller_lower_->robot_status_.temp_err_ ||
406  controller_upper_->robot_status_.temp_err_;
407 
408  robot_status_.res_err_ = controller_lower_->robot_status_.res_err_ ||
409  controller_upper_->robot_status_.res_err_;
410 
411  robot_status_.step_out_err_ = controller_lower_->robot_status_.step_out_err_ ||
412  controller_upper_->robot_status_.step_out_err_;
413 
414  robot_status_.p_stopped_err_ = controller_lower_->robot_status_.p_stopped_err_ ||
415  controller_upper_->robot_status_.p_stopped_err_;
416 
417  robot_status_.power_err_ = controller_lower_->robot_status_.power_err_ ||
418  controller_upper_->robot_status_.power_err_;
419 
420  diagnostic_updater_.update();
421 
422  }
423 
424  void RobotHW::setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
425  {
426  if(comm_err_ ){
427  stat.summary(2,"Now calibrating, or the USB cable is plugged out");
428  }
429  else if(robot_status_.power_err_ ){
430  stat.summary(2,"Power failed, pleae check the battery");
431  }
433  stat.summary(2,"Connection error occurred, please check the cable");
434  }
435  else if( robot_status_.temp_err_ ){
436  stat.summary(2,"Motor driver is high temperature, please reboot the robot");
437  }
438  else if(robot_status_.p_stopped_err_){
439  stat.summary(2,"Protective stopped, please release it");
440  }
441  else if(robot_status_.calib_err_ ){
442  stat.summary(2,"Calibration error occurred, please recalibration");
443  }
444  else if(robot_status_.step_out_err_ ){
445  stat.summary(1,"Step-out has occurred");
446  }
447  else if( robot_status_.res_err_ ){
448  stat.summary(1,"Response error has occurred");
449  }
450  else{
451  stat.summary(0,"System all green");
452  }
453 
455  stat.summary(2,"E-Stop switch is pushed, please release it");
456  }
457 
458  stat.add("Communication Error", comm_err_);
459  stat.add("Emergency Stopped", robot_status_.connection_err_ && robot_status_.calib_err_ );
460  stat.add("Protective Stopped",robot_status_.p_stopped_err_);
461  stat.add("Connection Error",robot_status_.connection_err_);
462  stat.add("Calibration Error",robot_status_.calib_err_);
463  stat.add("Motor Servo OFF",robot_status_.motor_err_);
464  stat.add("Temperature Error",robot_status_.temp_err_);
465  stat.add("Response Error",robot_status_.res_err_);
466  stat.add("Step Out Occurred",robot_status_.step_out_err_);
467  stat.add("Power Failed",robot_status_.power_err_);
468 
469  }
470 
472  (seed_r7_ros_controller::ResetRobotStatus::Request& _req,
473  seed_r7_ros_controller::ResetRobotStatus::Response& _res)
474  {
475 
476  ROS_WARN("reset robot status");
477  mutex_lower_.lock();
478  controller_lower_->getRobotStatus(0xFF);
479  mutex_lower_.unlock();
480 
481  _res.result = "reset status succeeded";
482 
483  return true;
484  }
485 
486 }
void turnWheel(std::vector< int16_t > &_vel)
hardware_interface::JointStateInterface js_interface_
void publish(const boost::shared_ptr< M > &message) const
void runLedScript(uint8_t _number, uint16_t _script)
URDF_EXPORT bool initString(const std::string &xmlstring)
bool resetRobotStatusCallback(seed_r7_ros_controller::ResetRobotStatus::Request &_req, seed_r7_ros_controller::ResetRobotStatus::Response &_res)
void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::shared_ptr< seed_converter::StrokeConverter > stroke_converter_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
#define ROS_WARN(...)
boost::shared_ptr< robot_hardware::UpperController > controller_upper_
void enforceLimits(const ros::Duration &period)
struct robot_hardware::RobotHW::RobotStatus robot_status_
std::vector< std::string > joint_names_upper_
std::vector< std::string > joint_names_lower_
boost::shared_ptr< robot_hardware::LowerController > controller_lower_
std::vector< double > joint_position_
pluginlib::ClassLoader< seed_converter::StrokeConverter > converter_loader_
std::vector< double > prev_ref_strokes_
std::vector< double > joint_effort_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::vector< double > joint_position_command_
std::vector< double > joint_effort_command_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void getBatteryVoltage(const ros::TimerEvent &_event)
hardware_interface::PositionJointInterface pj_interface_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< JointType > joint_types_
std::vector< ControlMethod > joint_control_methods_
void registerHandle(const JointStateHandle &handle)
void readPos(const ros::Time &time, const ros::Duration &period, bool update)
JointStateHandle getHandle(const std::string &name)
ros::ServiceServer reset_robot_status_server_
diagnostic_updater::Updater diagnostic_updater_
bool getParam(const std::string &key, std::string &s) const
std::vector< double > joint_velocity_
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
static Time now()
std::vector< std::string > joint_list_
std::vector< double > joint_velocity_command_
bool hasParam(const std::string &key) const
virtual void read(const ros::Time &time, const ros::Duration &period)
#define ROS_ERROR(...)
void runHandScript(uint8_t _number, uint16_t _script, uint8_t _current)
virtual void write(const ros::Time &time, const ros::Duration &period)
#define ROS_DEBUG(...)
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)


seed_r7_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sun Apr 18 2021 02:40:34