robot.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2016 SoftBank Robotics Europe
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <sensor_msgs/JointState.h>
19 
20 #include <diagnostic_msgs/DiagnosticArray.h>
21 
22 #include <XmlRpcValue.h>
23 
26 
28  isConnected,
29  connect,
30  stopService);
31 
32 Robot::Robot(qi::SessionPtr session):
33  _session(session),
34  session_name_("naoqi_dcm_driver"),
35  is_connected_(false),
36  nhPtr_(new ros::NodeHandle("")),
37  body_type_(""),
38  topic_queue_(10),
39  prefix_("naoqi_dcm"),
40  high_freq_(50.0),
41  controller_freq_(15.0),
42  joint_precision_(0.1),
43  odom_frame_("odom"),
44  use_dcm_(false),
45  stiffness_value_(0.9f)
46 {
47 }
48 
49 Robot::~Robot()
50 {
51  stopService();
52 }
53 
54 void Robot::stopService() {
55  ROS_INFO_STREAM(session_name_ << " stopping the service...");
56 
57  if (motion_)
58  {
59  /* reset stiffness for arms if using DCM
60  * to prevent its concurrence with ALMotion */
61  if(use_dcm_)
62  motion_->setStiffnessArms(0.0f, 2.0f);
63 
64  //going to rest
65  if (motor_groups_.size() == 1)
66  if (motor_groups_[0] == "Body")
67  motion_->rest();
68 
69  //set stiffness for the whole body
70  //setStiffness(0.0f);
71  motion_->setStiffnessArms(0.0f, 2.0f);
72  }
73 
74  is_connected_ = false;
75 
76  if(nhPtr_)
77  {
78  nhPtr_->shutdown();
79  ros::shutdown();
80  }
81 }
82 
83 bool Robot::initializeControllers(const std::vector <std::string> &joints)
84 {
85  int joints_nbr = joints.size();
86 
87  // Initialize Controllers' Interfaces
88  hw_angles_.reserve(joints_nbr);
89  hw_velocities_.reserve(joints_nbr);
90  hw_efforts_.reserve(joints_nbr);
91  hw_commands_.reserve(joints_nbr);
92 
93  hw_angles_.resize(joints_nbr);
94  hw_velocities_.resize(joints_nbr);
95  hw_efforts_.resize(joints_nbr);
96  hw_commands_.resize(joints_nbr);
97 
98  try
99  {
100  for(int i=0; i<joints_nbr; ++i)
101  {
102  hardware_interface::JointStateHandle state_handle(joints.at(i),
103  &hw_angles_[i],
104  &hw_velocities_[i],
105  &hw_efforts_[i]);
106  jnt_state_interface_.registerHandle(state_handle);
107 
108  hardware_interface::JointHandle pos_handle(jnt_state_interface_.getHandle(joints.at(i)),
109  &hw_commands_[i]);
110  jnt_pos_interface_.registerHandle(pos_handle);
111  }
112 
113  registerInterface(&jnt_state_interface_);
114  registerInterface(&jnt_pos_interface_);
115  }
116  catch(const ros::Exception& e)
117  {
118  ROS_ERROR("Could not initialize hardware interfaces!\n\tTrace: %s", e.what());
119  return false;
120  }
121 
122  return true;
123 }
124 
125 // The entry point from outside
126 bool Robot::connect()
127 {
128  is_connected_ = false;
129 
130  // Load ROS Parameters
131  if (!loadParams())
132  return false;
133 
134  // Initialize DCM Wrapper
135  if (use_dcm_)
136  dcm_ = boost::shared_ptr<DCM>(new DCM(_session, controller_freq_));
137 
138  // Initialize Memory Wrapper
139  memory_ = boost::shared_ptr<Memory>(new Memory(_session));
140 
141  //get the robot's name
142  std::string robot = memory_->getData("RobotConfig/Body/Type");
143  std::transform(robot.begin(), robot.end(), robot.begin(), ::tolower);
144 
145  // Initialize Motion Wrapper
146  motion_ = boost::shared_ptr<Motion>(new Motion(_session));
147 
148  // check if the robot is waked up
149  if (motor_groups_.size() == 1)
150  {
151  if (motor_groups_[0] == "Body")
152  motion_->wakeUp();
153  }
154  else if (!use_dcm_)
155  motion_->wakeUp();
156  if (!motion_->robotIsWakeUp())
157  {
158  ROS_ERROR("Please, wakeUp the robot to be able to set stiffness");
159  stopService();
160  return false;
161  }
162 
163  if (use_dcm_)
164  motion_->manageConcurrence();
165 
166  //read Naoqi joints names that will be controlled
167  qi_joints_ = motion_->getBodyNamesFromGroup(motor_groups_);
168  if (qi_joints_.empty())
169  ROS_ERROR("Controlled joints are not known.");
170  //define HW joints if empty
171  if (hw_joints_.empty())
172  {
173  ROS_INFO_STREAM("Initializing the HW controlled joints with Naoqi joints.");
174  hw_joints_.reserve(qi_joints_.size());
175  copy(qi_joints_.begin(), qi_joints_.end(), back_inserter(hw_joints_));
176  }
177  ROS_INFO_STREAM("HW controlled joints are : " << print(hw_joints_));
178 
179  ignoreMimicJoints(&qi_joints_);
180  ROS_INFO_STREAM("Naoqi controlled joints are : " << print(qi_joints_));
181  qi_commands_.reserve(qi_joints_.size());
182  qi_commands_.resize(qi_joints_.size(), 0.0);
183 
184  //initialise Memory, Motion, and DCM classes with controlled joints
185  memory_->init(qi_joints_);
186  motion_->init(qi_joints_);
187  if (use_dcm_)
188  dcm_->init(qi_joints_);
189 
190  hw_enabled_ = checkJoints();
191 
192  //read joints names to initialize the joint_states topic
193  joint_states_topic_.header.frame_id = "base_link";
194  joint_states_topic_.name = motion_->getBodyNames("Body"); //Body=JointActuators+Wheels
195  joint_states_topic_.position.resize(joint_states_topic_.name.size());
196 
197  //read joints names to initialize the diagnostics
198  std::vector<std::string> joints_all_names = motion_->getBodyNames("JointActuators");
199  diagnostics_ = boost::shared_ptr<Diagnostics>(
200  new Diagnostics(_session, &diag_pub_, joints_all_names, robot));
201 
202  is_connected_ = true;
203 
204  // Subscribe/Publish ROS Topics/Services
205  subscribe();
206 
207  // Turn Stiffness On
208  if (!setStiffness(stiffness_value_))
209  return false;
210 
211  // Initialize Controller Manager and Controllers
212  try
213  {
214  manager_ = new controller_manager::ControllerManager( this, *nhPtr_);
215  }
216  catch(const ros::Exception& e)
217  {
218  ROS_ERROR("Could not initialize controller manager!\n\tTrace: %s", e.what());
219  return false;
220  }
221 
222  if(!initializeControllers(hw_joints_))
223  return false;
224 
225  ROS_INFO_STREAM(session_name_ << " module initialized!");
226  return true;
227 }
228 
229 void Robot::subscribe()
230 {
231  // Subscribe/Publish ROS Topics/Services
232  cmd_moveto_sub_ = nhPtr_->subscribe(prefix_+"cmd_moveto", 1, &Robot::commandVelocity, this);
233 
234  diag_pub_ = nhPtr_->advertise<diagnostic_msgs::DiagnosticArray>(prefix_+"diagnostics", topic_queue_);
235 
236  stiffness_pub_ = nhPtr_->advertise<std_msgs::Float32>(prefix_+"stiffnesses", topic_queue_);
237  stiffness_.data = 1.0f;
238 
239  joint_states_pub_ = nhPtr_->advertise<sensor_msgs::JointState>("/joint_states", topic_queue_);
240 }
241 
242 bool Robot::loadParams()
243 {
244  ros::NodeHandle nh("~");
245  // Load Server Parameters
246  nh.getParam("BodyType", body_type_);
247  nh.getParam("TopicQueue", topic_queue_);
248  nh.getParam("HighCommunicationFrequency", high_freq_);
249  nh.getParam("ControllerFrequency", controller_freq_);
250  nh.getParam("JointPrecision", joint_precision_);
251  nh.getParam("OdomFrame", odom_frame_);
252  nh.getParam("use_dcm", use_dcm_);
253 
254  if (nh.hasParam("max_stiffness"))
255  nh.getParam("max_stiffness", stiffness_value_);
256 
257  if (use_dcm_)
258  ROS_WARN_STREAM("Please, be carefull! "
259  << "You have chosen to control the robot based on DCM. "
260  << "It leads to concurrence between DCM and ALMotion, and "
261  << "it can cause shaking the robot. "
262  << "If the robot starts shaking, stop the node (Ctrl+C). "
263  << "Use either ALMotion or stop ALMotion and use DCM only.");
264 
265  //set the prefix for topics
266  nh.getParam("Prefix", prefix_);
267  if (prefix_.length() > 0)
268  if (prefix_.at(prefix_.length()-1) != '/')
269  prefix_ += "/";
270 
271  //read HW controllers names
272  XmlRpc::XmlRpcValue params_pepper_dcm;
273  nh.getParam("pepper_dcm", params_pepper_dcm);
274  if (params_pepper_dcm.getType() != XmlRpc::XmlRpcValue::TypeStruct)
275  ROS_ERROR("Please ensure that the list of controllers is TypeStruct");
276 
277  XmlRpc::XmlRpcValue::ValueStruct::const_iterator it=params_pepper_dcm.begin();
278  for (; it != params_pepper_dcm.end(); ++it)
279  {
280  XmlRpc::XmlRpcValue::ValueStruct::const_iterator it2 = params_pepper_dcm[it->first].begin();
281  for (; it2 != params_pepper_dcm[it->first].end(); ++it2)
282  {
283  std::string param = (std::string)(it2->first);
284  if (param.compare("joints") == 0)
285  {
286  XmlRpc::XmlRpcValue params_joints = params_pepper_dcm[it->first][it2->first];
287  if (params_joints.getType() == XmlRpc::XmlRpcValue::TypeArray)
288  {
289  xmlToVector(params_joints, &hw_joints_);
290  continue;
291  }
292  }
293  }
294  }
295 
296  //define the motors groups to control
297  std::string motor_groups_temp = "";
298  nh.getParam("motor_groups", motor_groups_temp);
299  motor_groups_ = toVector(motor_groups_temp);
300  if (motor_groups_.empty())
301  {
302  motor_groups_.push_back("LArm");
303  motor_groups_.push_back("RArm");
304  }
305  return true;
306 }
307 
308 void Robot::run()
309 {
310  controllerLoop();
311 }
312 
313 void Robot::controllerLoop()
314 {
315  static ros::Rate rate(controller_freq_);
316  while(ros::ok())
317  {
318  ros::Time time = ros::Time::now();
319 
320  if(!is_connected_)
321  break;
322 
323  //publishBaseFootprint(time);
324 
325  stiffness_pub_.publish(stiffness_);
326 
327  if (!diagnostics_->publish())
328  stopService();
329 
330  readJoints();
331 
332  //motion_->stiffnessInterpolation(diagnostics_->getForcedJoints(), 0.3f, 2.0f);
333 
334  try
335  {
336  manager_->update(time, ros::Duration(1.0f/controller_freq_));
337  }
338  catch(ros::Exception& e)
339  {
340  ROS_ERROR("%s", e.what());
341  return;
342  }
343 
344  writeJoints();
345 
346  //no need if Naoqi Driver is running
347  //publishJointStateFromAlMotion();
348 
349  rate.sleep();
350  }
351  ROS_INFO_STREAM("Shutting down the main loop");
352 }
353 
354 bool Robot::isConnected()
355 {
356  return is_connected_;
357 }
358 
359 void Robot::commandVelocity(const geometry_msgs::TwistConstPtr &msg)
360 {
361  //reset stiffness for arms if using DCM to prevent its concurrence with ALMotion
362  if(use_dcm_)
363  motion_->setStiffnessArms(0.0f, 1.0f);
364 
365  motion_->moveTo(msg->linear.x, msg->linear.y, msg->angular.z);
366  sleep(1.0);
367 
368  //set stiffness for arms if using DCM
369  if(use_dcm_)
370  motion_->setStiffnessArms(1.0f, 1.0f);
371 }
372 
373 void Robot::publishBaseFootprint(const ros::Time &ts)
374 {
375  std::string odom_frame, base_link_frame;
376  try
377  {
378  odom_frame = base_footprint_listener_.resolve(odom_frame_);
379  base_link_frame = base_footprint_listener_.resolve("base_link");
380  }
381  catch(ros::Exception& e)
382  {
383  ROS_ERROR("%s", e.what());
384  return;
385  }
386 
387  tf::StampedTransform tf_odom_to_base, tf_odom_to_left_foot, tf_odom_to_right_foot;
388  double temp_freq = 1.0f/(10.0*high_freq_);
389  if(!base_footprint_listener_.waitForTransform(odom_frame, base_link_frame, ros::Time(0), ros::Duration(temp_freq)))
390  return;
391  try
392  {
393  base_footprint_listener_.lookupTransform(odom_frame, base_link_frame, ros::Time(0), tf_odom_to_base);
394  }
395  catch (const tf::TransformException& ex)
396  {
397  ROS_ERROR("%s",ex.what());
398  return ;
399  }
400 
401  tf::Vector3 new_origin = (tf_odom_to_right_foot.getOrigin() + tf_odom_to_left_foot.getOrigin())/2.0;
402  double height = std::min(tf_odom_to_left_foot.getOrigin().getZ(), tf_odom_to_right_foot.getOrigin().getZ());
403  new_origin.setZ(height);
404 
405  double roll, pitch, yaw;
406  tf_odom_to_base.getBasis().getRPY(roll, pitch, yaw);
407 
408  tf::Transform tf_odom_to_footprint(tf::createQuaternionFromYaw(yaw), new_origin);
409  tf::Transform tf_base_to_footprint = tf_odom_to_base.inverse() * tf_odom_to_footprint;
410 
411  base_footprint_broadcaster_.sendTransform(tf::StampedTransform(tf_base_to_footprint, ts,
412  base_link_frame, "base_footprint"));
413 }
414 
415 std::vector <bool> Robot::checkJoints()
416 {
417  std::vector <bool> hw_enabled;
418  hw_enabled.reserve(hw_joints_.size());
419  hw_enabled.resize(hw_joints_.size(), false);
420 
421  //store joints angles
422  std::vector<std::string>::iterator hw_j = hw_joints_.begin();
423  std::vector<std::string>::iterator qi_j = qi_joints_.begin();
424  std::vector<bool>::iterator hw_enabled_j = hw_enabled.begin();
425 
426  for(; hw_j != hw_joints_.end(); ++hw_j, ++hw_enabled_j)
427  {
428  if (*hw_j == *qi_j)
429  {
430  *hw_enabled_j = true;
431  ++qi_j;
432  }
433  }
434  return hw_enabled;
435 }
436 
437 void Robot::readJoints()
438 {
439  //read memory keys for joint/position/sensor
440  std::vector<float> qi_joints_positions = memory_->getListData();
441 
442  //store joints angles
443  std::vector<double>::iterator hw_command_j = hw_commands_.begin();
444  std::vector<double>::iterator hw_angle_j = hw_angles_.begin();
445  std::vector<float>::iterator qi_position_j = qi_joints_positions.begin();
446  std::vector<bool>::iterator hw_enabled_j = hw_enabled_.begin();
447 
448  for(; hw_command_j != hw_commands_.end(); ++hw_command_j, ++hw_angle_j, ++hw_enabled_j)
449  {
450  if (!*hw_enabled_j)
451  continue;
452 
453  *hw_angle_j = *qi_position_j;
454  // Set commands to the read angles for when no command specified
455  *hw_command_j = *qi_position_j;
456 
457  //increment qi iterators
458  ++qi_position_j;
459  }
460 }
461 
462 void Robot::publishJointStateFromAlMotion(){
463  joint_states_topic_.header.stamp = ros::Time::now();
464 
465  std::vector<double> position_data = motion_->getAngles("Body");
466  for(int i = 0; i<position_data.size(); ++i)
467  joint_states_topic_.position[i] = position_data[i];
468 
469  joint_states_pub_.publish(joint_states_topic_);
470 }
471 
472 void Robot::writeJoints()
473 {
474  // Check if there is some change in joints values
475  bool changed(false);
476  std::vector<double>::iterator hw_angle_j = hw_angles_.begin();
477  std::vector<double>::iterator hw_command_j = hw_commands_.begin();
478  std::vector<double>::iterator qi_command_j = qi_commands_.begin();
479  std::vector<bool>::iterator hw_enabled_j = hw_enabled_.begin();
480  for(int i=0; hw_command_j != hw_commands_.end(); ++i, ++hw_command_j, ++hw_angle_j, ++hw_enabled_j)
481  {
482  if (!*hw_enabled_j)
483  continue;
484 
485  *qi_command_j = *hw_command_j;
486  ++qi_command_j;
487 
488  double diff = std::fabs(*hw_command_j - *hw_angle_j);
489  if(diff > joint_precision_)
490  {
491  //ROS_INFO_STREAM(" joint " << i << " : diff=" << diff);
492  changed = true;
493  }
494  }
495 
496  // Update joints values if there are some changes
497  if(!changed)
498  return;
499 
500  if (use_dcm_)
501  dcm_->writeJoints(qi_commands_);
502  else
503  motion_->writeJoints(qi_commands_);
504 }
505 
506 void Robot::ignoreMimicJoints(std::vector <std::string> *joints)
507 {
508  //ignore mimic joints
509  for(std::vector<std::string>::iterator it=joints->begin(); it!=joints->end(); ++it)
510  {
511  if( (it->find("Wheel") != std::string::npos)
512  || (*it=="RHand" || *it=="LHand" || *it == "RWristYaw" || *it == "LWristYaw") && (body_type_ == "H21"))
513  {
514  joints->erase(it);
515  it--;
516  }
517  }
518 }
519 
520 // rewrite by calling DCM rather than ALMotion
521 bool Robot::setStiffness(const float &stiffness)
522 {
523  stiffness_.data = stiffness;
524 
525  if (!motion_->stiffnessInterpolation(motor_groups_, stiffness, 2.0f))
526  return false;
527 
528  return true;
529 }
This class is a wapper for Naoqi DCM Class.
Definition: dcm.hpp:27
void xmlToVector(XmlRpc::XmlRpcValue &topicList, std::vector< std::string > *joints)
Definition: tools.cpp:137
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::string print(const std::vector< std::string > &vector)
Definition: tools.cpp:110
Definition: robot.hpp:59
f
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
void subscribe()
static Quaternion createQuaternionFromYaw(double yaw)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Motion(const qi::SessionPtr &session)
Definition: motion.cpp:24
ROSCPP_DECL bool ok()
Transform inverse() const
#define ROS_WARN_STREAM(args)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void writeJoints(const std::vector< double > &joint_commands)
set joints values
Definition: motion.cpp:200
This class is a wapper for Naoqi Memory Class.
Definition: memory.hpp:27
#define ROS_INFO_STREAM(args)
std::vector< std::string > toVector(const std::string &input)
Definition: tools.cpp:121
static Time now()
ROSCPP_DECL void shutdown()
QI_REGISTER_OBJECT(Robot, isConnected, connect, stopService)
This class defines a Diagnostic It is used to check the robot state and sent to requesting nodes...
Definition: diagnostics.hpp:30
#define ROS_ERROR(...)


naoqi_dcm_driver
Author(s): Konstantinos Chatzilygeroudis , Mikael Arguedas , Karsten Knese , Natalia Lyubova
autogenerated on Thu Jul 25 2019 03:49:27