cob_undercarriage_ctrl.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_driver
00012  * ROS package name: cob_undercarriage_ctrl
00013  * Description:
00014  *                                                              
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *                      
00017  * Author: Christian Connette, email:christian.connette@ipa.fhg.de
00018  * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de
00019  *
00020  * Date of creation: April 2010:
00021  * ToDo: Adapt Interface to controller -> remove last variable (not used anymore)
00022  *       Rework Ctrl-class to work with SI-Units -> remove conversion
00023  *               For easier association of joints use platform.urdf!!
00024  *
00025  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00026  *
00027  * Redistribution and use in source and binary forms, with or without
00028  * modification, are permitted provided that the following conditions are met:
00029  *
00030  *     * Redistributions of source code must retain the above copyright
00031  *       notice, this list of conditions and the following disclaimer.
00032  *     * Redistributions in binary form must reproduce the above copyright
00033  *       notice, this list of conditions and the following disclaimer in the
00034  *       documentation and/or other materials provided with the distribution.
00035  *     * Neither the name of the Fraunhofer Institute for Manufacturing 
00036  *       Engineering and Automation (IPA) nor the names of its
00037  *       contributors may be used to endorse or promote products derived from
00038  *       this software without specific prior written permission.
00039  *
00040  * This program is free software: you can redistribute it and/or modify
00041  * it under the terms of the GNU Lesser General Public License LGPL as 
00042  * published by the Free Software Foundation, either version 3 of the 
00043  * License, or (at your option) any later version.
00044  * 
00045  * This program is distributed in the hope that it will be useful,
00046  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00047  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00048  * GNU Lesser General Public License LGPL for more details.
00049  * 
00050  * You should have received a copy of the GNU Lesser General Public 
00051  * License LGPL along with this program. 
00052  * If not, see <http://www.gnu.org/licenses/>.
00053  *
00054  ****************************************************************/
00055 
00056 //##################
00057 //#### includes ####
00058 
00059 // standard includes
00060 #include <math.h>
00061 
00062 // ROS includes
00063 #include <ros/ros.h>
00064 
00065 // ROS message includes
00066 #include <sensor_msgs/JointState.h>
00067 #include <diagnostic_msgs/DiagnosticStatus.h>
00068 #include <diagnostic_updater/diagnostic_updater.h>
00069 #include <geometry_msgs/Twist.h>
00070 #include <nav_msgs/Odometry.h>
00071 #include <tf/transform_broadcaster.h>
00072 #include <cob_relayboard/EmergencyStopState.h>
00073 #include <control_msgs/JointTrajectoryControllerState.h>
00074 
00075 // external includes
00076 #include <cob_undercarriage_ctrl/UndercarriageCtrlGeom.h>
00077 #include <cob_utilities/IniFile.h>
00078 //#include <cob_utilities/MathSup.h>
00079 
00080 //####################
00081 //#### node class ####
00082 class NodeClass
00083 {
00084   //
00085   public:
00086     // create a handle for this node, initialize node
00087     ros::NodeHandle n;
00088 
00089     // topics to publish
00090     ros::Publisher topic_pub_joint_state_cmd_;  // cmd issued for single joints of undercarriage
00091     ros::Publisher topic_pub_controller_joint_command_;
00092     ros::Publisher topic_pub_odometry_;                 // calculated (measured) velocity, rotation and pose (odometry-based) for the robot
00093     tf::TransformBroadcaster tf_broadcast_odometry_;    // according transformation for the tf broadcaster
00094 
00095     // topics to subscribe, callback is called for new messages arriving
00096     ros::Subscriber topic_sub_CMD_pltf_twist_;  // issued command to be achieved by the platform
00097     ros::Subscriber topic_sub_EM_stop_state_;   // current emergency stop state (free, active, confirmed)
00098     ros::Subscriber topic_sub_drive_diagnostic_;// status of drive chain (initializing, error, normal)
00099 
00100     //subscribe to JointStates topic
00101     //ros::Subscriber topic_sub_joint_states_;
00102     ros::Subscriber topic_sub_joint_controller_states_;
00103 
00104     // diagnostic stuff
00105     diagnostic_updater::Updater updater_;
00106 
00107     // controller Timer
00108     ros::Timer timer_ctrl_step_;
00109 
00110     // member variables
00111     UndercarriageCtrlGeom * ucar_ctrl_; // instantiate undercarriage controller
00112     std::string sIniDirectory;
00113     bool is_initialized_bool_;                  // flag wether node is already up and running
00114     bool broadcast_tf_;                 // flag wether to broadcast the tf from odom to base_link
00115     int drive_chain_diagnostic_;                // flag whether base drive chain is operating normal 
00116     ros::Time last_time_;                               // time Stamp for last odometry measurement
00117     ros::Time joint_state_odom_stamp_;  // time stamp of joint states used for current odometry calc
00118     double sample_time_, timeout_;
00119     double x_rob_m_, y_rob_m_, theta_rob_rad_; // accumulated motion of robot since startup
00120     int iwatchdog_;
00121     double      vel_x_rob_last_, vel_y_rob_last_, vel_theta_rob_last_; //save velocities for better odom calculation
00122     double max_vel_trans_, max_vel_rot_;
00123 
00124     int m_iNumJoints;
00125 
00126     diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_; // used to access defines for warning levels
00127 
00128     // Constructor
00129     NodeClass()
00130     {
00131       // initialization of variables
00132       is_initialized_bool_ = false;
00133       broadcast_tf_ = true;
00134       iwatchdog_ = 0;
00135       last_time_ = ros::Time::now();
00136       sample_time_ = 0.020;
00137       x_rob_m_ = 0.0;
00138       y_rob_m_ = 0.0;
00139       theta_rob_rad_ = 0.0;
00140       vel_x_rob_last_ = 0.0;
00141       vel_y_rob_last_ = 0.0;
00142       vel_theta_rob_last_ = 0.0;
00143       // set status of drive chain to WARN by default
00144       drive_chain_diagnostic_ = diagnostic_status_lookup_.OK; //WARN; <- THATS FOR DEBUGGING ONLY!
00145 
00146       // Parameters are set within the launch file
00147       // read in timeout for watchdog stopping the controller.
00148       if (n.hasParam("timeout"))
00149       {
00150         n.getParam("timeout", timeout_);
00151         ROS_INFO("Timeout loaded from Parameter-Server is: %fs", timeout_);
00152       }
00153       else
00154       {
00155         ROS_WARN("No parameter timeout on Parameter-Server. Using default: 1.0s");
00156         timeout_ = 1.0;
00157       }
00158       if ( timeout_ < sample_time_ )
00159       {
00160         ROS_WARN("Specified timeout < sample_time. Setting timeout to sample_time = %fs", sample_time_);
00161         timeout_ = sample_time_;
00162       }
00163 
00164       // Read number of drives from iniFile and pass IniDirectory to CobPlatfCtrl.
00165       if (n.hasParam("IniDirectory"))
00166       {
00167         n.getParam("IniDirectory", sIniDirectory);
00168         ROS_INFO("IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
00169       }
00170       else
00171       {
00172         sIniDirectory = "Platform/IniFiles/";
00173         ROS_WARN("IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
00174       }
00175 
00176       if (n.hasParam("max_trans_velocity"))
00177       {
00178         n.getParam("max_trans_velocity", max_vel_trans_);
00179         ROS_INFO("Max translational velocity loaded from Parameter-Server is: %fs", max_vel_trans_);
00180       }
00181       else
00182       {
00183         ROS_WARN("No parameter max_trans_velocity on Parameter-Server. Using default: 1.1 m/s");
00184         max_vel_trans_ = 1.1;
00185       }
00186       if (n.hasParam("max_rot_velocity"))
00187       {
00188         n.getParam("max_rot_velocity", max_vel_rot_);
00189         ROS_INFO("Max rotational velocity loaded from Parameter-Server is: %fs", max_vel_rot_);
00190       }
00191       else
00192       {
00193         ROS_WARN("No parameter max_rot_velocity on Parameter-Server. Using default: 1.8 rad/s");
00194         max_vel_rot_ = 1.8;
00195       }
00196       if (n.hasParam("broadcast_tf"))
00197       {
00198         n.getParam("broadcast_tf", broadcast_tf_);
00199       }
00200 
00201       IniFile iniFile;
00202       iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
00203       iniFile.GetKeyInt("Config", "NumberOfMotors", &m_iNumJoints, true);
00204 
00205       ucar_ctrl_ = new UndercarriageCtrlGeom(sIniDirectory);
00206 
00207 
00208       // implementation of topics
00209       // published topics
00210       //topic_pub_joint_state_cmd_ = n.advertise<sensor_msgs::JointState>("joint_command", 1);
00211       topic_pub_controller_joint_command_ = n.advertise<control_msgs::JointTrajectoryControllerState> ("joint_command", 1);
00212 
00213       topic_pub_odometry_ = n.advertise<nav_msgs::Odometry>("odometry", 1);
00214 
00215       // subscribed topics
00216       topic_sub_CMD_pltf_twist_ = n.subscribe("command", 1, &NodeClass::topicCallbackTwistCmd, this);
00217       topic_sub_EM_stop_state_ = n.subscribe("/emergency_stop_state", 1, &NodeClass::topicCallbackEMStop, this);
00218       topic_sub_drive_diagnostic_ = n.subscribe("diagnostic", 1, &NodeClass::topicCallbackDiagnostic, this);
00219 
00220 
00221 
00222       //topic_sub_joint_states_ = n.subscribe("/joint_states", 1, &NodeClass::topicCallbackJointStates, this);
00223       topic_sub_joint_controller_states_ = n.subscribe("state", 1, &NodeClass::topicCallbackJointControllerStates, this);
00224 
00225       // diagnostics
00226       updater_.setHardwareID(ros::this_node::getName());
00227       updater_.add("initialization", this, &NodeClass::diag_init);
00228 
00229       //set up timer to cyclically call controller-step
00230       timer_ctrl_step_ = n.createTimer(ros::Duration(sample_time_), &NodeClass::timerCallbackCtrlStep, this);
00231 
00232     }
00233 
00234     // Destructor
00235     ~NodeClass() 
00236     {
00237     }
00238 
00239     void diag_init(diagnostic_updater::DiagnosticStatusWrapper &stat)
00240     {
00241       if(is_initialized_bool_)
00242         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "");
00243       else
00244         stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "");
00245       stat.add("Initialized", is_initialized_bool_);
00246     }
00247 
00248     // Listen for Pltf Cmds
00249     void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr& msg)
00250     {
00251       double vx_cmd_mms, vy_cmd_mms, w_cmd_rads;
00252 
00253       if( (fabs(msg->linear.x) > max_vel_trans_) || (fabs(msg->linear.y) > max_vel_trans_) || (fabs(msg->angular.z) > max_vel_rot_))
00254       {
00255         if(fabs(msg->linear.x) > max_vel_trans_)
00256         {
00257           ROS_DEBUG_STREAM("Recevied cmdVelX: " << msg->linear.x << 
00258               ", which is bigger than the maximal allowed translational velocity: " <<  max_vel_trans_ << " so stop the robot");
00259         }
00260         if(fabs(msg->linear.y) > max_vel_trans_)
00261         {
00262           ROS_DEBUG_STREAM("Recevied cmdVelY: " << msg->linear.x << 
00263               ", which is bigger than the maximal allowed translational velocity: " <<  max_vel_trans_ << " so stop the robot");
00264         }
00265 
00266         if(fabs(msg->angular.z) > max_vel_rot_)
00267         {
00268           ROS_DEBUG_STREAM("Recevied cmdVelTh: " << msg->angular.z << 
00269               ", which is bigger than the maximal allowed rotational velocity: " << max_vel_rot_ << " so stop the robot");
00270         }
00271         vx_cmd_mms = 0.0;
00272         vy_cmd_mms = 0.0;
00273         w_cmd_rads = 0.0;
00274       }
00275       else
00276       {
00277         // controller expects velocities in mm/s, ROS works with SI-Units -> convert
00278         // ToDo: rework Controller Class to work with SI-Units
00279         vx_cmd_mms = msg->linear.x*1000.0;      
00280         vy_cmd_mms = msg->linear.y*1000.0;
00281         w_cmd_rads = msg->angular.z;
00282       }
00283 
00284       iwatchdog_ = 0;
00285 
00286       // only process if controller is already initialized
00287       if (is_initialized_bool_ && drive_chain_diagnostic_==diagnostic_status_lookup_.OK)
00288       {
00289         ROS_DEBUG("received new velocity command [cmdVelX=%3.5f,cmdVelY=%3.5f,cmdVelTh=%3.5f]", 
00290             msg->linear.x, msg->linear.y, msg->angular.z);
00291 
00292         // Set desired value for Plattform Velocity to UndercarriageCtrl (setpoint setting)
00293         ucar_ctrl_->SetDesiredPltfVelocity(vx_cmd_mms, vy_cmd_mms, w_cmd_rads, 0.0);
00294         // ToDo: last value (0.0) is not used anymore --> remove from interface
00295       }
00296       else
00297       { 
00298         // Set desired value for Plattform Velocity to zero (setpoint setting)
00299         ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00300         // ToDo: last value (0.0) is not used anymore --> remove from interface
00301         ROS_DEBUG("Forced platform-velocity cmds to zero");
00302       }
00303 
00304     }
00305 
00306     // Listen for Emergency Stop
00307     void topicCallbackEMStop(const cob_relayboard::EmergencyStopState::ConstPtr& msg)
00308     {
00309       int EM_state;
00310       EM_state = msg->emergency_state;
00311 
00312       if (EM_state == msg->EMFREE)
00313       {
00314         // Reset EM flag in Ctrlr
00315         if (is_initialized_bool_) 
00316         {
00317           ucar_ctrl_->setEMStopActive(false);
00318           ROS_DEBUG("Undercarriage Controller EM-Stop released");
00319           // reset only done, when system initialized
00320           // -> allows to stop ctrlr during init, reset and shutdown
00321         }
00322       }
00323       else
00324       {
00325         ROS_DEBUG("Undercarriage Controller stopped due to EM-Stop");
00326 
00327         // Set desired value for Plattform Velocity to zero (setpoint setting)
00328         ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00329         // ToDo: last value (0.0) is not used anymore --> remove from interface
00330         ROS_DEBUG("Forced platform-velocity cmds to zero");
00331 
00332         // Set EM flag and stop Ctrlr
00333         ucar_ctrl_->setEMStopActive(true);
00334       }
00335     }
00336 
00337     // Listens for status of underlying hardware (base drive chain)
00338     void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr& msg)
00339     {
00340       control_msgs::JointTrajectoryControllerState joint_state_cmd;
00341 
00342       // prepare joint_cmds for heartbeat (compose header)
00343       joint_state_cmd.header.stamp = ros::Time::now();
00344       //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
00345       // ToDo: configure over Config-File (number of motors) and Msg
00346       // assign right size to JointState data containers
00347       //joint_state_cmd.set_name_size(m_iNumMotors);
00348       joint_state_cmd.desired.positions.resize(m_iNumJoints);
00349       joint_state_cmd.desired.velocities.resize(m_iNumJoints);            
00350       //joint_state_cmd.desired.effort.resize(m_iNumJoints);
00351       joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00352       joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00353       joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00354       joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00355       joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00356       joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00357       joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00358       joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00359       joint_state_cmd.joint_names.resize(m_iNumJoints);
00360 
00361       // compose jointcmds
00362       for(int i=0; i<m_iNumJoints; i++)
00363       {
00364         joint_state_cmd.desired.positions[i] = 0.0;
00365         joint_state_cmd.desired.velocities[i] = 0.0;
00366         //joint_state_cmd.desired.effort[i] = 0.0;
00367       }
00368 
00369       // set status of underlying drive chain to member variable 
00370       drive_chain_diagnostic_ = msg->level;
00371 
00372       // if controller is already started up ...
00373       if (is_initialized_bool_)
00374       {
00375         // ... but underlying drive chain is not yet operating normal
00376         if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00377         {
00378           // halt controller
00379           ROS_DEBUG("drive chain not availlable: halt Controller");
00380 
00381           // Set EM flag to Ctrlr (resets internal states)
00382           ucar_ctrl_->setEMStopActive(true);
00383 
00384           // Set desired value for Plattform Velocity to zero (setpoint setting)
00385           ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00386           // ToDo: last value (0.0) is not used anymore --> remove from interface
00387           ROS_DEBUG("Forced platform-velocity cmds to zero");
00388 
00389           // if is not Initializing
00390           if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00391           {
00392             // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
00393             // this is already done in CalcControlStep
00394           }
00395         }
00396       }
00397       // ... while controller is not initialized send heartbeats to keep motors alive
00398       else
00399       {
00400         // ... as soon as base drive chain is initialized
00401         if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00402         {
00403           // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
00404           topic_pub_controller_joint_command_.publish(joint_state_cmd);
00405         }
00406       }
00407     }
00408 
00409     void topicCallbackJointControllerStates(const control_msgs::JointTrajectoryControllerState::ConstPtr& msg) {
00410       int num_joints;
00411       int iter_k, iter_j;
00412       std::vector<double> drive_joint_ang_rad, drive_joint_vel_rads, drive_joint_effort_NM;
00413       std::vector<double> steer_joint_ang_rad, steer_joint_vel_rads, steer_joint_effort_NM;
00414 
00415       joint_state_odom_stamp_ = msg->header.stamp;
00416 
00417       // copy configuration into vector classes
00418       num_joints = msg->joint_names.size();
00419       // drive joints
00420       drive_joint_ang_rad.assign(m_iNumJoints, 0.0);
00421       drive_joint_vel_rads.assign(m_iNumJoints, 0.0);
00422       drive_joint_effort_NM.assign(m_iNumJoints, 0.0);
00423       // steer joints
00424       steer_joint_ang_rad.assign(m_iNumJoints, 0.0);
00425       steer_joint_vel_rads.assign(m_iNumJoints, 0.0);
00426       steer_joint_effort_NM.assign(m_iNumJoints, 0.0);
00427 
00428       // init iterators
00429       iter_k = 0;
00430       iter_j = 0;
00431 
00432       for(int i = 0; i < num_joints; i++)
00433       {
00434         // associate inputs to according steer and drive joints
00435         // ToDo: specify this globally (Prms-File or config-File or via msg-def.)       
00436         if(msg->joint_names[i] ==  "fl_caster_r_wheel_joint")
00437         {
00438           drive_joint_ang_rad[0] = msg->actual.positions[i]; 
00439           drive_joint_vel_rads[0] = msg->actual.velocities[i];
00440           //drive_joint_effort_NM[0] = msg->effort[i];
00441         }
00442         if(msg->joint_names[i] ==  "bl_caster_r_wheel_joint")
00443         {
00444           drive_joint_ang_rad[1] = msg->actual.positions[i]; 
00445           drive_joint_vel_rads[1] = msg->actual.velocities[i];
00446           //drive_joint_effort_NM[1] = msg->effort[i];
00447         }
00448         if(msg->joint_names[i] ==  "br_caster_r_wheel_joint")
00449         {
00450           drive_joint_ang_rad[2] = msg->actual.positions[i]; 
00451           drive_joint_vel_rads[2] = msg->actual.velocities[i];
00452           //drive_joint_effort_NM[2] = msg->effort[i];
00453         }
00454         if(msg->joint_names[i] ==  "fr_caster_r_wheel_joint")
00455         {
00456           drive_joint_ang_rad[3] = msg->actual.positions[i]; 
00457           drive_joint_vel_rads[3] = msg->actual.velocities[i];
00458           //drive_joint_effort_NM[3] = msg->effort[i];
00459         }
00460         if(msg->joint_names[i] ==  "fl_caster_rotation_joint")
00461         {
00462           steer_joint_ang_rad[0] = msg->actual.positions[i]; 
00463           steer_joint_vel_rads[0] = msg->actual.velocities[i];
00464           //steer_joint_effort_NM[0] = msg->effort[i];
00465         }
00466         if(msg->joint_names[i] ==  "bl_caster_rotation_joint")
00467         { 
00468           steer_joint_ang_rad[1] = msg->actual.positions[i]; 
00469           steer_joint_vel_rads[1] = msg->actual.velocities[i];
00470           //steer_joint_effort_NM[1] = msg->effort[i];
00471         }
00472         if(msg->joint_names[i] ==  "br_caster_rotation_joint")
00473         {
00474           steer_joint_ang_rad[2] = msg->actual.positions[i]; 
00475           steer_joint_vel_rads[2] = msg->actual.velocities[i];
00476           //steer_joint_effort_NM[2] = msg->effort[i];
00477         }
00478         if(msg->joint_names[i] ==  "fr_caster_rotation_joint")
00479         {
00480           steer_joint_ang_rad[3] = msg->actual.positions[i]; 
00481           steer_joint_vel_rads[3] = msg->actual.velocities[i];
00482           //steer_joint_effort_NM[3] = msg->effort[i];
00483         }
00484       }
00485 
00486       // Set measured Wheel Velocities and Angles to Controler Class (implements inverse kinematic)
00487       ucar_ctrl_->SetActualWheelValues(drive_joint_vel_rads, steer_joint_vel_rads,
00488           drive_joint_ang_rad, steer_joint_ang_rad);
00489 
00490 
00491       // calculate odometry every time
00492       UpdateOdometry();
00493 
00494     }
00495 
00496     void timerCallbackCtrlStep(const ros::TimerEvent& e) {
00497       CalcCtrlStep();
00498     }
00499 
00500     // other function declarations
00501     // Initializes controller
00502     bool InitCtrl();
00503     // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
00504     void CalcCtrlStep();
00505     // acquires the current undercarriage configuration from base_drive_chain
00506     // calculates odometry from current measurement values and publishes it via an odometry topic and the tf broadcaster
00507     void UpdateOdometry();
00508 };
00509 
00510 //#######################
00511 //#### main programm ####
00512 int main(int argc, char** argv)
00513 {
00514   // initialize ROS, spezify name of node
00515   ros::init(argc, argv, "undercarriage_ctrl");
00516 
00517   // construct nodeClass
00518   NodeClass nodeClass;
00519 
00520   // automatically do initializing of controller, because it's not directly depending any hardware components
00521   nodeClass.ucar_ctrl_->InitUndercarriageCtrl();
00522   nodeClass.is_initialized_bool_ = true;
00523 
00524   if( nodeClass.is_initialized_bool_ ) {
00525     nodeClass.last_time_ = ros::Time::now();
00526     ROS_INFO("Undercarriage control successfully initialized.");
00527   } else {
00528     ROS_FATAL("Undercarriage control initialization failed!");
00529     throw std::runtime_error("Undercarriage control initialization failed, check ini-Files!");
00530   }
00531 
00532   /* 
00533      CALLBACKS being executed are:
00534      - actual motor values -> calculating direct kinematics and doing odometry (topicCallbackJointControllerStates)
00535      - timer callback -> calculate controller step at a rate of sample_time_ (timerCallbackCtrlStep)
00536      - other topic callbacks (diagnostics, command, em_stop_state)
00537      */
00538   ros::spin();
00539 
00540   return 0;
00541 }
00542 
00543 //##################################
00544 //#### function implementations ####
00545 
00546 // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
00547 void NodeClass::CalcCtrlStep()
00548 {
00549   double vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy;
00550   std::vector<double> drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad;
00551   control_msgs::JointTrajectoryControllerState joint_state_cmd;
00552   int j, k;
00553   iwatchdog_ += 1;      
00554 
00555   // if controller is initialized and underlying hardware is operating normal
00556   if (is_initialized_bool_) //&& (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK))
00557   {
00558     // as soon as (but only as soon as) platform drive chain is initialized start to send velocity commands
00559     // Note: topicCallbackDiagnostic checks whether drives are operating nominal.
00560     //       -> if warning or errors are issued target velocity is set to zero
00561 
00562     // perform one control step,
00563     // get the resulting cmd's for the wheel velocities and -angles from the controller class
00564     // and output the achievable pltf velocity-cmds (if velocity limits where exceeded)
00565     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);
00566     // ToDo: adapt interface of controller class --> remove last values (not used anymore)
00567 
00568     // if drives not operating nominal -> force commands to zero
00569     if(drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00570     {
00571       steer_jointang_cmds_rad.assign(m_iNumJoints, 0.0);
00572       steer_jointvel_cmds_rads.assign(m_iNumJoints, 0.0);
00573     }
00574 
00575     // convert variables to SI-Units
00576     vx_cmd_ms = vx_cmd_ms/1000.0;
00577     vy_cmd_ms = vy_cmd_ms/1000.0;
00578 
00579     // compose jointcmds
00580     // compose header
00581     joint_state_cmd.header.stamp = ros::Time::now();
00582     //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
00583     // ToDo: configure over Config-File (number of motors) and Msg
00584     // assign right size to JointState data containers
00585     //joint_state_cmd.set_name_size(m_iNumMotors);
00586     joint_state_cmd.desired.positions.resize(m_iNumJoints);
00587     joint_state_cmd.desired.velocities.resize(m_iNumJoints);            
00588     //joint_state_cmd.effort.resize(m_iNumJoints);
00589     joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00590     joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00591     joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00592     joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00593     joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00594     joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00595     joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00596     joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00597     joint_state_cmd.joint_names.resize(m_iNumJoints);
00598 
00599     // compose data body
00600     j = 0;
00601     k = 0;
00602     for(int i = 0; i<m_iNumJoints; i++)
00603     {
00604       if(iwatchdog_ < (int) std::floor(timeout_/sample_time_) )
00605       {
00606         // for steering motors
00607         if( i == 1 || i == 3 || i == 5 || i == 7) // ToDo: specify this via the Msg
00608         {
00609           joint_state_cmd.desired.positions[i] = steer_jointang_cmds_rad[j];
00610           joint_state_cmd.desired.velocities[i] = steer_jointvel_cmds_rads[j];
00611           //joint_state_cmd.effort[i] = 0.0;
00612           j = j + 1;
00613         }
00614         else
00615         {
00616           joint_state_cmd.desired.positions[i] = 0.0;
00617           joint_state_cmd.desired.velocities[i] = drive_jointvel_cmds_rads[k];
00618           //joint_state_cmd.effort[i] = 0.0;
00619           k = k + 1;
00620         }
00621       }
00622       else
00623       {
00624         joint_state_cmd.desired.positions[i] = 0.0;
00625         joint_state_cmd.desired.velocities[i] = 0.0;
00626         //joint_state_cmd.effort[i] = 0.0;
00627       }
00628     }
00629 
00630     // publish jointcmds
00631     topic_pub_controller_joint_command_.publish(joint_state_cmd);
00632   }
00633 
00634 }
00635 
00636 // calculates odometry from current measurement values
00637 // and publishes it via an odometry topic and the tf broadcaster
00638 void NodeClass::UpdateOdometry()
00639 {
00640   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;
00641   double dummy1, dummy2;
00642   double dt;
00643   ros::Time current_time;
00644 
00645   // if drive chain already initialized process joint data
00646   //if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00647   if (is_initialized_bool_)
00648   {
00649     // Get resulting Pltf Velocities from Ctrl-Class (result of forward kinematics)
00650     // !Careful! Controller internally calculates with mm instead of m
00651     // ToDo: change internal calculation to SI-Units
00652     // ToDo: last values are not used anymore --> remove from interface
00653     ucar_ctrl_->GetActualPltfVelocity(delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad, dummy1,
00654         vel_x_rob_ms, vel_y_rob_ms, rot_rob_rads, dummy2);
00655 
00656     // convert variables to SI-Units
00657     vel_x_rob_ms = vel_x_rob_ms/1000.0;
00658     vel_y_rob_ms = vel_y_rob_ms/1000.0;
00659     delta_x_rob_m = delta_x_rob_m/1000.0;
00660     delta_y_rob_m = delta_y_rob_m/1000.0;
00661 
00662     ROS_DEBUG("Odmonetry delta is: x=%f, y=%f, th=%f", delta_x_rob_m, delta_y_rob_m, rot_rob_rads);
00663   }
00664   else
00665   {
00666     // otherwise set data (velocity and pose-delta) to zero
00667     vel_x_rob_ms = 0.0;
00668     vel_y_rob_ms = 0.0;
00669     delta_x_rob_m = 0.0;
00670     delta_y_rob_m = 0.0;
00671   }
00672 
00673   // calc odometry (from startup)
00674   // get time since last odometry-measurement
00675   current_time = ros::Time::now();
00676   dt = current_time.toSec() - last_time_.toSec();
00677   last_time_ = current_time;
00678   vel_rob_ms = sqrt(vel_x_rob_ms*vel_x_rob_ms + vel_y_rob_ms*vel_y_rob_ms);
00679 
00680   // calculation from ROS odom publisher tutorial http://www.ros.org/wiki/navigation/Tutorials/RobotSetup/Odom, using now midpoint integration
00681   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;
00682   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;
00683   theta_rob_rad_ = theta_rob_rad_ + rot_rob_rads * dt;
00684   //theta_rob_rad_ = theta_rob_rad_ + (rot_rob_rads+vel_theta_rob_last_)/2.0 * dt;
00685 
00686   vel_x_rob_last_ = vel_x_rob_ms;
00687   vel_y_rob_last_ = vel_y_rob_ms;
00688   vel_theta_rob_last_ = rot_rob_rads;
00689 
00690 
00691   // format data for compatibility with tf-package and standard odometry msg
00692   // generate quaternion for rotation
00693   geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00694 
00695   if (broadcast_tf_ == true)
00696   {
00697     // compose and publish transform for tf package
00698     geometry_msgs::TransformStamped odom_tf;
00699     // compose header
00700     odom_tf.header.stamp = joint_state_odom_stamp_;
00701     odom_tf.header.frame_id = "/odom_combined";
00702     odom_tf.child_frame_id = "/base_footprint";
00703     // compose data container
00704     odom_tf.transform.translation.x = x_rob_m_;
00705     odom_tf.transform.translation.y = y_rob_m_;
00706     odom_tf.transform.translation.z = 0.0;
00707     odom_tf.transform.rotation = odom_quat;
00708 
00709     // publish the transform (for debugging, conflicts with robot-pose-ekf)
00710     tf_broadcast_odometry_.sendTransform(odom_tf);
00711   }
00712 
00713   // compose and publish odometry message as topic
00714   nav_msgs::Odometry odom_top;
00715   // compose header
00716   odom_top.header.stamp = joint_state_odom_stamp_;
00717   odom_top.header.frame_id = "/wheelodom";
00718   odom_top.child_frame_id = "/base_footprint";
00719   // compose pose of robot
00720   odom_top.pose.pose.position.x = x_rob_m_;
00721   odom_top.pose.pose.position.y = y_rob_m_;
00722   odom_top.pose.pose.position.z = 0.0;
00723   odom_top.pose.pose.orientation = odom_quat;
00724   for(int i = 0; i < 6; i++)
00725     odom_top.pose.covariance[i*6+i] = 0.1;
00726 
00727   // compose twist of robot
00728   odom_top.twist.twist.linear.x = vel_x_rob_ms;
00729   odom_top.twist.twist.linear.y = vel_y_rob_ms;
00730   odom_top.twist.twist.linear.z = 0.0;
00731   odom_top.twist.twist.angular.x = 0.0;
00732   odom_top.twist.twist.angular.y = 0.0;
00733   odom_top.twist.twist.angular.z = rot_rob_rads;
00734   for(int i = 0; i < 6; i++)
00735     odom_top.twist.covariance[6*i+i] = 0.1;
00736 
00737   // publish odometry msg
00738   topic_pub_odometry_.publish(odom_top);
00739 }
00740 
00741 
00742 
00743 


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Thu Aug 27 2015 12:45:53