cob_undercarriage_ctrl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
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 //##################
19 //#### includes ####
20 
21 // standard includes
22 #include <math.h>
23 
24 // ROS includes
25 #include <ros/ros.h>
26 
27 // ROS message includes
28 #include <diagnostic_msgs/DiagnosticStatus.h>
30 #include <geometry_msgs/Twist.h>
31 #include <nav_msgs/Odometry.h>
33 #include <cob_msgs/EmergencyStopState.h>
34 #include <control_msgs/JointTrajectoryControllerState.h>
35 
36 // external includes
38 #include <cob_utilities/IniFile.h>
39 //#include <cob_utilities/MathSup.h>
40 
41 //####################
42 //#### node class ####
43 class NodeClass
44 {
45  //
46  public:
47  // create a handle for this node, initialize node
49 
50  // topics to publish
51  ros::Publisher topic_pub_joint_state_cmd_; // cmd issued for single joints of undercarriage
53  ros::Publisher topic_pub_odometry_; // calculated (measured) velocity, rotation and pose (odometry-based) for the robot
54  tf::TransformBroadcaster tf_broadcast_odometry_; // according transformation for the tf broadcaster
55 
56  // topics to subscribe, callback is called for new messages arriving
57  ros::Subscriber topic_sub_CMD_pltf_twist_; // issued command to be achieved by the platform
58  ros::Subscriber topic_sub_EM_stop_state_; // current emergency stop state (free, active, confirmed)
59  ros::Subscriber topic_sub_drive_diagnostic_;// status of drive chain (initializing, error, normal)
60 
61  //subscribe to JointStates topic
62  //ros::Subscriber topic_sub_joint_states_;
64 
65  // diagnostic stuff
67 
68  // controller Timer
70 
71  // member variables
72  UndercarriageCtrlGeom * ucar_ctrl_; // instantiate undercarriage controller
73  std::string sIniDirectory;
74  bool is_initialized_bool_; // flag wether node is already up and running
75  bool broadcast_tf_; // flag wether to broadcast the tf from odom to base_link
76  int drive_chain_diagnostic_; // flag whether base drive chain is operating normal
77  ros::Time last_time_; // time Stamp for last odometry measurement
78  ros::Time joint_state_odom_stamp_; // time stamp of joint states used for current odometry calc
80  double x_rob_m_, y_rob_m_, theta_rob_rad_; // accumulated motion of robot since startup
82  double vel_x_rob_last_, vel_y_rob_last_, vel_theta_rob_last_; //save velocities for better odom calculation
84 
86 
87  diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_; // used to access defines for warning levels
88 
89  // Constructor
91  {
92  // initialization of variables
93  is_initialized_bool_ = false;
94  broadcast_tf_ = true;
95  iwatchdog_ = 0;
96  last_time_ = ros::Time::now();
97  sample_time_ = 0.020;
98  x_rob_m_ = 0.0;
99  y_rob_m_ = 0.0;
100  theta_rob_rad_ = 0.0;
101  vel_x_rob_last_ = 0.0;
102  vel_y_rob_last_ = 0.0;
103  vel_theta_rob_last_ = 0.0;
104  // set status of drive chain to WARN by default
105  drive_chain_diagnostic_ = diagnostic_status_lookup_.OK; //WARN; <- THATS FOR DEBUGGING ONLY!
106 
107  // Parameters are set within the launch file
108  // read in timeout for watchdog stopping the controller.
109  if (n.hasParam("timeout"))
110  {
111  n.getParam("timeout", timeout_);
112  ROS_INFO("Timeout loaded from Parameter-Server is: %fs", timeout_);
113  }
114  else
115  {
116  ROS_WARN("No parameter timeout on Parameter-Server. Using default: 1.0s");
117  timeout_ = 1.0;
118  }
119  if ( timeout_ < sample_time_ )
120  {
121  ROS_WARN("Specified timeout < sample_time. Setting timeout to sample_time = %fs", sample_time_);
122  timeout_ = sample_time_;
123  }
124 
125  // Read number of drives from iniFile and pass IniDirectory to CobPlatfCtrl.
126  if (n.hasParam("IniDirectory"))
127  {
128  n.getParam("IniDirectory", sIniDirectory);
129  ROS_INFO("IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
130  }
131  else
132  {
133  sIniDirectory = "Platform/IniFiles/";
134  ROS_WARN("IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
135  }
136 
137  if (n.hasParam("max_trans_velocity"))
138  {
139  n.getParam("max_trans_velocity", max_vel_trans_);
140  ROS_INFO("Max translational velocity loaded from Parameter-Server is: %fs", max_vel_trans_);
141  }
142  else
143  {
144  ROS_WARN("No parameter max_trans_velocity on Parameter-Server. Using default: 1.1 m/s");
145  max_vel_trans_ = 1.1;
146  }
147  if (n.hasParam("max_rot_velocity"))
148  {
149  n.getParam("max_rot_velocity", max_vel_rot_);
150  ROS_INFO("Max rotational velocity loaded from Parameter-Server is: %fs", max_vel_rot_);
151  }
152  else
153  {
154  ROS_WARN("No parameter max_rot_velocity on Parameter-Server. Using default: 1.8 rad/s");
155  max_vel_rot_ = 1.8;
156  }
157  if (n.hasParam("broadcast_tf"))
158  {
159  n.getParam("broadcast_tf", broadcast_tf_);
160  }
161 
162  IniFile iniFile;
163  iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
164  iniFile.GetKeyInt("Config", "NumberOfMotors", &m_iNumJoints, true);
165 
166  ucar_ctrl_ = new UndercarriageCtrlGeom(sIniDirectory);
167 
168 
169  // implementation of topics
170  // published topics
171  //topic_pub_joint_state_cmd_ = n.advertise<sensor_msgs::JointState>("joint_command", 1);
172  topic_pub_controller_joint_command_ = n.advertise<control_msgs::JointTrajectoryControllerState> ("joint_command", 1);
173 
174  topic_pub_odometry_ = n.advertise<nav_msgs::Odometry>("odometry", 1);
175 
176  // subscribed topics
177  topic_sub_CMD_pltf_twist_ = n.subscribe("command", 1, &NodeClass::topicCallbackTwistCmd, this);
178  topic_sub_EM_stop_state_ = n.subscribe("/emergency_stop_state", 1, &NodeClass::topicCallbackEMStop, this);
179  topic_sub_drive_diagnostic_ = n.subscribe("diagnostic", 1, &NodeClass::topicCallbackDiagnostic, this);
180 
181 
182 
183  //topic_sub_joint_states_ = n.subscribe("/joint_states", 1, &NodeClass::topicCallbackJointStates, this);
184  topic_sub_joint_controller_states_ = n.subscribe("state", 1, &NodeClass::topicCallbackJointControllerStates, this);
185 
186  // diagnostics
188  updater_.add("initialization", this, &NodeClass::diag_init);
189 
190  //set up timer to cyclically call controller-step
191  timer_ctrl_step_ = n.createTimer(ros::Duration(sample_time_), &NodeClass::timerCallbackCtrlStep, this);
192 
193  }
194 
195  // Destructor
197  {
198  }
199 
201  {
202  if(is_initialized_bool_)
203  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "");
204  else
205  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "");
206  stat.add("Initialized", is_initialized_bool_);
207  }
208 
209  // Listen for Pltf Cmds
210  void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr& msg)
211  {
212  double vx_cmd_mms, vy_cmd_mms, w_cmd_rads;
213 
214  // check for NaN value in Twist message
215  if(isnan(msg->linear.x) || isnan(msg->linear.y) || isnan(msg->angular.z)) {
216  iwatchdog_ = 0;
217  ROS_FATAL("Received NaN-value in Twist message. Stopping the robot.");
218  // force platform velocity commands to zero;
219  ucar_ctrl_->SetDesiredPltfVelocity(0.0, 0.0, 0.0, 0.0);
220  ROS_DEBUG("Forced platform velocity commands to zero");
221  return;
222  }
223 
224  if( (fabs(msg->linear.x) > max_vel_trans_) || (fabs(msg->linear.y) > max_vel_trans_) || (fabs(msg->angular.z) > max_vel_rot_))
225  {
226  if(fabs(msg->linear.x) > max_vel_trans_)
227  {
228  ROS_DEBUG_STREAM("Recevied cmdVelX: " << msg->linear.x <<
229  ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ << " so stop the robot");
230  }
231  if(fabs(msg->linear.y) > max_vel_trans_)
232  {
233  ROS_DEBUG_STREAM("Recevied cmdVelY: " << msg->linear.x <<
234  ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ << " so stop the robot");
235  }
236 
237  if(fabs(msg->angular.z) > max_vel_rot_)
238  {
239  ROS_DEBUG_STREAM("Recevied cmdVelTh: " << msg->angular.z <<
240  ", which is bigger than the maximal allowed rotational velocity: " << max_vel_rot_ << " so stop the robot");
241  }
242  vx_cmd_mms = 0.0;
243  vy_cmd_mms = 0.0;
244  w_cmd_rads = 0.0;
245  }
246  else
247  {
248  // controller expects velocities in mm/s, ROS works with SI-Units -> convert
249  // ToDo: rework Controller Class to work with SI-Units
250  vx_cmd_mms = msg->linear.x*1000.0;
251  vy_cmd_mms = msg->linear.y*1000.0;
252  w_cmd_rads = msg->angular.z;
253  }
254 
255  iwatchdog_ = 0;
256 
257  // only process if controller is already initialized
258  if (is_initialized_bool_ && drive_chain_diagnostic_==diagnostic_status_lookup_.OK)
259  {
260  ROS_DEBUG("received new velocity command [cmdVelX=%3.5f,cmdVelY=%3.5f,cmdVelTh=%3.5f]",
261  msg->linear.x, msg->linear.y, msg->angular.z);
262 
263  // Set desired value for Plattform Velocity to UndercarriageCtrl (setpoint setting)
264  ucar_ctrl_->SetDesiredPltfVelocity(vx_cmd_mms, vy_cmd_mms, w_cmd_rads, 0.0);
265  // ToDo: last value (0.0) is not used anymore --> remove from interface
266  }
267  else
268  {
269  // Set desired value for Plattform Velocity to zero (setpoint setting)
270  ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
271  // ToDo: last value (0.0) is not used anymore --> remove from interface
272  ROS_DEBUG("Forced platform-velocity cmds to zero");
273  }
274 
275  }
276 
277  // Listen for Emergency Stop
278  void topicCallbackEMStop(const cob_msgs::EmergencyStopState::ConstPtr& msg)
279  {
280  int EM_state;
281  EM_state = msg->emergency_state;
282 
283  if (EM_state == msg->EMFREE)
284  {
285  // Reset EM flag in Ctrlr
286  if (is_initialized_bool_)
287  {
288  ucar_ctrl_->setEMStopActive(false);
289  ROS_DEBUG("Undercarriage Controller EM-Stop released");
290  // reset only done, when system initialized
291  // -> allows to stop ctrlr during init, reset and shutdown
292  }
293  }
294  else
295  {
296  ROS_DEBUG("Undercarriage Controller stopped due to EM-Stop");
297 
298  // Set desired value for Plattform Velocity to zero (setpoint setting)
299  ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
300  // ToDo: last value (0.0) is not used anymore --> remove from interface
301  ROS_DEBUG("Forced platform-velocity cmds to zero");
302 
303  // Set EM flag and stop Ctrlr
304  ucar_ctrl_->setEMStopActive(true);
305  }
306  }
307 
308  // Listens for status of underlying hardware (base drive chain)
309  void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr& msg)
310  {
311  control_msgs::JointTrajectoryControllerState joint_state_cmd;
312 
313  // prepare joint_cmds for heartbeat (compose header)
314  joint_state_cmd.header.stamp = ros::Time::now();
315  //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
316  // ToDo: configure over Config-File (number of motors) and Msg
317  // assign right size to JointState data containers
318  //joint_state_cmd.set_name_size(m_iNumMotors);
319  joint_state_cmd.desired.positions.resize(m_iNumJoints);
320  joint_state_cmd.desired.velocities.resize(m_iNumJoints);
321  //joint_state_cmd.desired.effort.resize(m_iNumJoints);
322  joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
323  joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
324  joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
325  joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
326  joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
327  joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
328  joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
329  joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
330  joint_state_cmd.joint_names.resize(m_iNumJoints);
331 
332  // compose jointcmds
333  for(int i=0; i<m_iNumJoints; i++)
334  {
335  joint_state_cmd.desired.positions[i] = 0.0;
336  joint_state_cmd.desired.velocities[i] = 0.0;
337  //joint_state_cmd.desired.effort[i] = 0.0;
338  }
339 
340  // set status of underlying drive chain to member variable
341  drive_chain_diagnostic_ = msg->level;
342 
343  // if controller is already started up ...
344  if (is_initialized_bool_)
345  {
346  // ... but underlying drive chain is not yet operating normal
347  if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
348  {
349  // halt controller
350  ROS_DEBUG("drive chain not availlable: halt Controller");
351 
352  // Set EM flag to Ctrlr (resets internal states)
353  ucar_ctrl_->setEMStopActive(true);
354 
355  // Set desired value for Plattform Velocity to zero (setpoint setting)
356  ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
357  // ToDo: last value (0.0) is not used anymore --> remove from interface
358  ROS_DEBUG("Forced platform-velocity cmds to zero");
359 
360  // if is not Initializing
361  if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
362  {
363  // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
364  // this is already done in CalcControlStep
365  }
366  }
367  }
368  // ... while controller is not initialized send heartbeats to keep motors alive
369  else
370  {
371  // ... as soon as base drive chain is initialized
372  if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
373  {
374  // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
375  topic_pub_controller_joint_command_.publish(joint_state_cmd);
376  }
377  }
378  }
379 
380  void topicCallbackJointControllerStates(const control_msgs::JointTrajectoryControllerState::ConstPtr& msg) {
381  int num_joints;
382  int iter_k, iter_j;
383  std::vector<double> drive_joint_ang_rad, drive_joint_vel_rads, drive_joint_effort_NM;
384  std::vector<double> steer_joint_ang_rad, steer_joint_vel_rads, steer_joint_effort_NM;
385 
386  joint_state_odom_stamp_ = msg->header.stamp;
387 
388  // copy configuration into vector classes
389  num_joints = msg->joint_names.size();
390  // drive joints
391  drive_joint_ang_rad.assign(m_iNumJoints, 0.0);
392  drive_joint_vel_rads.assign(m_iNumJoints, 0.0);
393  drive_joint_effort_NM.assign(m_iNumJoints, 0.0);
394  // steer joints
395  steer_joint_ang_rad.assign(m_iNumJoints, 0.0);
396  steer_joint_vel_rads.assign(m_iNumJoints, 0.0);
397  steer_joint_effort_NM.assign(m_iNumJoints, 0.0);
398 
399  // init iterators
400  iter_k = 0;
401  iter_j = 0;
402 
403  for(int i = 0; i < num_joints; i++)
404  {
405  // associate inputs to according steer and drive joints
406  // ToDo: specify this globally (Prms-File or config-File or via msg-def.)
407  if(msg->joint_names[i] == "fl_caster_r_wheel_joint")
408  {
409  drive_joint_ang_rad[0] = msg->actual.positions[i];
410  drive_joint_vel_rads[0] = msg->actual.velocities[i];
411  //drive_joint_effort_NM[0] = msg->effort[i];
412  }
413  if(msg->joint_names[i] == "bl_caster_r_wheel_joint")
414  {
415  drive_joint_ang_rad[1] = msg->actual.positions[i];
416  drive_joint_vel_rads[1] = msg->actual.velocities[i];
417  //drive_joint_effort_NM[1] = msg->effort[i];
418  }
419  if(msg->joint_names[i] == "br_caster_r_wheel_joint")
420  {
421  drive_joint_ang_rad[2] = msg->actual.positions[i];
422  drive_joint_vel_rads[2] = msg->actual.velocities[i];
423  //drive_joint_effort_NM[2] = msg->effort[i];
424  }
425  if(msg->joint_names[i] == "fr_caster_r_wheel_joint")
426  {
427  drive_joint_ang_rad[3] = msg->actual.positions[i];
428  drive_joint_vel_rads[3] = msg->actual.velocities[i];
429  //drive_joint_effort_NM[3] = msg->effort[i];
430  }
431  if(msg->joint_names[i] == "fl_caster_rotation_joint")
432  {
433  steer_joint_ang_rad[0] = msg->actual.positions[i];
434  steer_joint_vel_rads[0] = msg->actual.velocities[i];
435  //steer_joint_effort_NM[0] = msg->effort[i];
436  }
437  if(msg->joint_names[i] == "bl_caster_rotation_joint")
438  {
439  steer_joint_ang_rad[1] = msg->actual.positions[i];
440  steer_joint_vel_rads[1] = msg->actual.velocities[i];
441  //steer_joint_effort_NM[1] = msg->effort[i];
442  }
443  if(msg->joint_names[i] == "br_caster_rotation_joint")
444  {
445  steer_joint_ang_rad[2] = msg->actual.positions[i];
446  steer_joint_vel_rads[2] = msg->actual.velocities[i];
447  //steer_joint_effort_NM[2] = msg->effort[i];
448  }
449  if(msg->joint_names[i] == "fr_caster_rotation_joint")
450  {
451  steer_joint_ang_rad[3] = msg->actual.positions[i];
452  steer_joint_vel_rads[3] = msg->actual.velocities[i];
453  //steer_joint_effort_NM[3] = msg->effort[i];
454  }
455  }
456 
457  // Set measured Wheel Velocities and Angles to Controler Class (implements inverse kinematic)
458  ucar_ctrl_->SetActualWheelValues(drive_joint_vel_rads, steer_joint_vel_rads,
459  drive_joint_ang_rad, steer_joint_ang_rad);
460 
461 
462  // calculate odometry every time
463  UpdateOdometry();
464 
465  }
466 
468  CalcCtrlStep();
469  }
470 
471  // other function declarations
472  // Initializes controller
473  bool InitCtrl();
474  // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
475  void CalcCtrlStep();
476  // acquires the current undercarriage configuration from base_drive_chain
477  // calculates odometry from current measurement values and publishes it via an odometry topic and the tf broadcaster
478  void UpdateOdometry();
479 };
480 
481 //#######################
482 //#### main programm ####
483 int main(int argc, char** argv)
484 {
485  // initialize ROS, spezify name of node
486  ros::init(argc, argv, "undercarriage_ctrl");
487 
488  // construct nodeClass
489  NodeClass nodeClass;
490 
491  // automatically do initializing of controller, because it's not directly depending any hardware components
492  nodeClass.ucar_ctrl_->InitUndercarriageCtrl();
493  nodeClass.is_initialized_bool_ = true;
494 
495  if( nodeClass.is_initialized_bool_ ) {
496  nodeClass.last_time_ = ros::Time::now();
497  ROS_INFO("Undercarriage control successfully initialized.");
498  } else {
499  ROS_FATAL("Undercarriage control initialization failed!");
500  throw std::runtime_error("Undercarriage control initialization failed, check ini-Files!");
501  }
502 
503  /*
504  CALLBACKS being executed are:
505  - actual motor values -> calculating direct kinematics and doing odometry (topicCallbackJointControllerStates)
506  - timer callback -> calculate controller step at a rate of sample_time_ (timerCallbackCtrlStep)
507  - other topic callbacks (diagnostics, command, em_stop_state)
508  */
509  ros::spin();
510 
511  return 0;
512 }
513 
514 //##################################
515 //#### function implementations ####
516 
517 // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
519 {
520  double vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy;
521  std::vector<double> drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad;
522  control_msgs::JointTrajectoryControllerState joint_state_cmd;
523  int j, k;
524  iwatchdog_ += 1;
525 
526  // if controller is initialized and underlying hardware is operating normal
527  if (is_initialized_bool_) //&& (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK))
528  {
529  // as soon as (but only as soon as) platform drive chain is initialized start to send velocity commands
530  // Note: topicCallbackDiagnostic checks whether drives are operating nominal.
531  // -> if warning or errors are issued target velocity is set to zero
532 
533  // perform one control step,
534  // get the resulting cmd's for the wheel velocities and -angles from the controller class
535  // and output the achievable pltf velocity-cmds (if velocity limits where exceeded)
536  ucar_ctrl_->GetNewCtrlStateSteerDriveSetValues(drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad, vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy);
537  // ToDo: adapt interface of controller class --> remove last values (not used anymore)
538 
539  // if drives not operating nominal -> force commands to zero
541  {
542  steer_jointang_cmds_rad.assign(m_iNumJoints, 0.0);
543  steer_jointvel_cmds_rads.assign(m_iNumJoints, 0.0);
544  }
545 
546  // convert variables to SI-Units
547  vx_cmd_ms = vx_cmd_ms/1000.0;
548  vy_cmd_ms = vy_cmd_ms/1000.0;
549 
550  // compose jointcmds
551  // compose header
552  joint_state_cmd.header.stamp = ros::Time::now();
553  //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
554  // ToDo: configure over Config-File (number of motors) and Msg
555  // assign right size to JointState data containers
556  //joint_state_cmd.set_name_size(m_iNumMotors);
557  joint_state_cmd.desired.positions.resize(m_iNumJoints);
558  joint_state_cmd.desired.velocities.resize(m_iNumJoints);
559  //joint_state_cmd.effort.resize(m_iNumJoints);
560  joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
561  joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
562  joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
563  joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
564  joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
565  joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
566  joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
567  joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
568  joint_state_cmd.joint_names.resize(m_iNumJoints);
569 
570  // compose data body
571  j = 0;
572  k = 0;
573  for(int i = 0; i<m_iNumJoints; i++)
574  {
575  if(iwatchdog_ < (int) std::floor(timeout_/sample_time_) )
576  {
577  // for steering motors
578  if( i == 1 || i == 3 || i == 5 || i == 7) // ToDo: specify this via the Msg
579  {
580  joint_state_cmd.desired.positions[i] = steer_jointang_cmds_rad[j];
581  joint_state_cmd.desired.velocities[i] = steer_jointvel_cmds_rads[j];
582  //joint_state_cmd.effort[i] = 0.0;
583  j = j + 1;
584  }
585  else
586  {
587  joint_state_cmd.desired.positions[i] = 0.0;
588  joint_state_cmd.desired.velocities[i] = drive_jointvel_cmds_rads[k];
589  //joint_state_cmd.effort[i] = 0.0;
590  k = k + 1;
591  }
592  }
593  else
594  {
595  joint_state_cmd.desired.positions[i] = 0.0;
596  joint_state_cmd.desired.velocities[i] = 0.0;
597  //joint_state_cmd.effort[i] = 0.0;
598  }
599  }
600 
601  // publish jointcmds
603  }
604 
605 }
606 
607 // calculates odometry from current measurement values
608 // and publishes it via an odometry topic and the tf broadcaster
610 {
611  double vel_x_rob_ms, vel_y_rob_ms, vel_rob_ms, rot_rob_rads, delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad;
612  double dummy1, dummy2;
613  double dt;
614  ros::Time current_time;
615 
616  // if drive chain already initialized process joint data
617  //if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
619  {
620  // Get resulting Pltf Velocities from Ctrl-Class (result of forward kinematics)
621  // !Careful! Controller internally calculates with mm instead of m
622  // ToDo: change internal calculation to SI-Units
623  // ToDo: last values are not used anymore --> remove from interface
624  ucar_ctrl_->GetActualPltfVelocity(delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad, dummy1,
625  vel_x_rob_ms, vel_y_rob_ms, rot_rob_rads, dummy2);
626 
627  // convert variables to SI-Units
628  vel_x_rob_ms = vel_x_rob_ms/1000.0;
629  vel_y_rob_ms = vel_y_rob_ms/1000.0;
630  delta_x_rob_m = delta_x_rob_m/1000.0;
631  delta_y_rob_m = delta_y_rob_m/1000.0;
632 
633  ROS_DEBUG("Odmonetry delta is: x=%f, y=%f, th=%f", delta_x_rob_m, delta_y_rob_m, rot_rob_rads);
634  }
635  else
636  {
637  // otherwise set data (velocity and pose-delta) to zero
638  vel_x_rob_ms = 0.0;
639  vel_y_rob_ms = 0.0;
640  delta_x_rob_m = 0.0;
641  delta_y_rob_m = 0.0;
642  }
643 
644  // calc odometry (from startup)
645  // get time since last odometry-measurement
646  current_time = ros::Time::now();
647  dt = current_time.toSec() - last_time_.toSec();
648  last_time_ = current_time;
649  vel_rob_ms = sqrt(vel_x_rob_ms*vel_x_rob_ms + vel_y_rob_ms*vel_y_rob_ms);
650 
651  // calculation from ROS odom publisher tutorial http://www.ros.org/wiki/navigation/Tutorials/RobotSetup/Odom, using now midpoint integration
652  x_rob_m_ = x_rob_m_ + ((vel_x_rob_ms+vel_x_rob_last_)/2.0 * cos(theta_rob_rad_) - (vel_y_rob_ms+vel_y_rob_last_)/2.0 * sin(theta_rob_rad_)) * dt;
653  y_rob_m_ = y_rob_m_ + ((vel_x_rob_ms+vel_x_rob_last_)/2.0 * sin(theta_rob_rad_) + (vel_y_rob_ms+vel_y_rob_last_)/2.0 * cos(theta_rob_rad_)) * dt;
654  theta_rob_rad_ = theta_rob_rad_ + rot_rob_rads * dt;
655  //theta_rob_rad_ = theta_rob_rad_ + (rot_rob_rads+vel_theta_rob_last_)/2.0 * dt;
656 
657  vel_x_rob_last_ = vel_x_rob_ms;
658  vel_y_rob_last_ = vel_y_rob_ms;
659  vel_theta_rob_last_ = rot_rob_rads;
660 
661 
662  // format data for compatibility with tf-package and standard odometry msg
663  // generate quaternion for rotation
664  geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
665 
666  if (broadcast_tf_ == true)
667  {
668  // compose and publish transform for tf package
669  geometry_msgs::TransformStamped odom_tf;
670  // compose header
671  odom_tf.header.stamp = joint_state_odom_stamp_;
672  odom_tf.header.frame_id = "odom_combined";
673  odom_tf.child_frame_id = "base_footprint";
674  // compose data container
675  odom_tf.transform.translation.x = x_rob_m_;
676  odom_tf.transform.translation.y = y_rob_m_;
677  odom_tf.transform.translation.z = 0.0;
678  odom_tf.transform.rotation = odom_quat;
679 
680  // publish the transform (for debugging, conflicts with robot-pose-ekf)
682  }
683 
684  // compose and publish odometry message as topic
685  nav_msgs::Odometry odom_top;
686  // compose header
687  odom_top.header.stamp = joint_state_odom_stamp_;
688  odom_top.header.frame_id = "odom_combined";
689  odom_top.child_frame_id = "base_footprint";
690  // compose pose of robot
691  odom_top.pose.pose.position.x = x_rob_m_;
692  odom_top.pose.pose.position.y = y_rob_m_;
693  odom_top.pose.pose.position.z = 0.0;
694  odom_top.pose.pose.orientation = odom_quat;
695  for(int i = 0; i < 6; i++)
696  odom_top.pose.covariance[i*6+i] = 0.1;
697 
698  // compose twist of robot
699  odom_top.twist.twist.linear.x = vel_x_rob_ms;
700  odom_top.twist.twist.linear.y = vel_y_rob_ms;
701  odom_top.twist.twist.linear.z = 0.0;
702  odom_top.twist.twist.angular.x = 0.0;
703  odom_top.twist.twist.angular.y = 0.0;
704  odom_top.twist.twist.angular.z = rot_rob_rads;
705  for(int i = 0; i < 6; i++)
706  odom_top.twist.covariance[6*i+i] = 0.1;
707 
708  // publish odometry msg
709  topic_pub_odometry_.publish(odom_top);
710 }
711 
712 
713 
714 
bool InitCtrl()
void topicCallbackEMStop(const cob_msgs::EmergencyStopState::ConstPtr &msg)
ros::Subscriber topic_sub_joint_controller_states_
std::string sIniDirectory
#define ROS_FATAL(...)
void setEMStopActive(bool bEMStopActive)
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
UndercarriageCtrlGeom * ucar_ctrl_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
tf::TransformBroadcaster tf_broadcast_odometry_
void add(const std::string &name, TaskFunction f)
ROSCPP_DECL const std::string & getName()
#define ROS_WARN(...)
diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_
void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
void GetNewCtrlStateSteerDriveSetValues(std::vector< double > &vdVelGearDriveRadS, std::vector< double > &vdVelGearSteerRadS, std::vector< double > &vdAngGearSteerRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
ros::Time joint_state_odom_stamp_
int GetKeyInt(const char *pSect, const char *pKey, int *pValue, bool bWarnIfNotfound=true)
#define ROS_INFO(...)
ros::Subscriber topic_sub_CMD_pltf_twist_
void sendTransform(const StampedTransform &transform)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
int main(int argc, char **argv)
ros::Subscriber topic_sub_drive_diagnostic_
void timerCallbackCtrlStep(const ros::TimerEvent &e)
diagnostic_updater::Updater updater_
int SetFileName(std::string fileName, std::string strIniFileUsedBy="", bool bCreate=false)
ros::NodeHandle n
ros::Publisher topic_pub_joint_state_cmd_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void diag_init(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Subscriber topic_sub_EM_stop_state_
bool getParam(const std::string &key, std::string &s) const
void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr &msg)
ros::Publisher topic_pub_controller_joint_command_
static Time now()
void SetActualWheelValues(std::vector< double > vdVelGearDriveRadS, std::vector< double > vdVelGearSteerRadS, std::vector< double > vdDltAngGearDriveRad, std::vector< double > vdAngGearSteerRad)
void add(const std::string &key, const T &val)
bool hasParam(const std::string &key) const
void GetActualPltfVelocity(double &dDeltaLongMM, double &dDeltaLatMM, double &dDeltaRotRobRad, double &dDeltaRotVelRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
ros::Timer timer_ctrl_step_
ros::Publisher topic_pub_odometry_
void topicCallbackJointControllerStates(const control_msgs::JointTrajectoryControllerState::ConstPtr &msg)
#define ROS_DEBUG(...)


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Wed Apr 7 2021 02:11:56