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 <pr2_controllers_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                 int drive_chain_diagnostic_;            // flag whether base drive chain is operating normal 
00115                 ros::Time last_time_;                           // time Stamp for last odometry measurement
00116                 ros::Time joint_state_odom_stamp_;      // time stamp of joint states used for current odometry calc
00117                 double sample_time_, timeout_;
00118                 double x_rob_m_, y_rob_m_, theta_rob_rad_; // accumulated motion of robot since startup
00119         int iwatchdog_;
00120         double  vel_x_rob_last_, vel_y_rob_last_, vel_theta_rob_last_; //save velocities for better odom calculation
00121                 
00122                 int m_iNumJoints;
00123                 
00124                 diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_; // used to access defines for warning levels
00125 
00126         // Constructor
00127         NodeClass()
00128         {
00129                         // initialization of variables
00130                         is_initialized_bool_ = false;
00131                         iwatchdog_ = 0;
00132                         last_time_ = ros::Time::now();
00133                         sample_time_ = 0.020;
00134                         x_rob_m_ = 0.0;
00135                         y_rob_m_ = 0.0;
00136                         theta_rob_rad_ = 0.0;
00137                         vel_x_rob_last_ = 0.0;
00138                         vel_y_rob_last_ = 0.0;
00139                         vel_theta_rob_last_ = 0.0;
00140                         // set status of drive chain to WARN by default
00141                         drive_chain_diagnostic_ = diagnostic_status_lookup_.OK; //WARN; <- THATS FOR DEBUGGING ONLY!
00142                         
00143                         // Parameters are set within the launch file
00144                         // read in timeout for watchdog stopping the controller.
00145                         if (n.hasParam("timeout"))
00146                         {
00147                           n.getParam("timeout", timeout_);
00148                           ROS_INFO("Timeout loaded from Parameter-Server is: %fs", timeout_);
00149                         }
00150                         else
00151                         {
00152                           ROS_WARN("No parameter timeout on Parameter-Server. Using default: 1.0s");
00153                           timeout_ = 1.0;
00154                         }
00155                         if ( timeout_ < sample_time_ )
00156                         {
00157                           ROS_WARN("Specified timeout < sample_time. Setting timeout to sample_time = %fs", sample_time_);
00158                           timeout_ = sample_time_;
00159                         }
00160                         
00161                         // Read number of drives from iniFile and pass IniDirectory to CobPlatfCtrl.
00162                         if (n.hasParam("IniDirectory"))
00163                         {
00164                                 n.getParam("IniDirectory", sIniDirectory);
00165                                 ROS_INFO("IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
00166                         }
00167                         else
00168                         {
00169                                 sIniDirectory = "Platform/IniFiles/";
00170                                 ROS_WARN("IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
00171                         }
00172 
00173                         IniFile iniFile;
00174                         iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
00175                         iniFile.GetKeyInt("Config", "NumberOfMotors", &m_iNumJoints, true);
00176                         
00177                         ucar_ctrl_ = new UndercarriageCtrlGeom(sIniDirectory);
00178                         
00179                         
00180                         // implementation of topics
00181             // published topics
00182                         //topic_pub_joint_state_cmd_ = n.advertise<sensor_msgs::JointState>("joint_command", 1);
00183                         topic_pub_controller_joint_command_ = n.advertise<pr2_controllers_msgs::JointTrajectoryControllerState> ("joint_command", 1);
00184 
00185                         topic_pub_odometry_ = n.advertise<nav_msgs::Odometry>("odometry", 1);
00186 
00187             // subscribed topics
00188                         topic_sub_CMD_pltf_twist_ = n.subscribe("command", 1, &NodeClass::topicCallbackTwistCmd, this);
00189             topic_sub_EM_stop_state_ = n.subscribe("/emergency_stop_state", 1, &NodeClass::topicCallbackEMStop, this);
00190             topic_sub_drive_diagnostic_ = n.subscribe("diagnostic", 1, &NodeClass::topicCallbackDiagnostic, this);
00191 
00192                         
00193                         
00194                         //topic_sub_joint_states_ = n.subscribe("/joint_states", 1, &NodeClass::topicCallbackJointStates, this);
00195                         topic_sub_joint_controller_states_ = n.subscribe("state", 1, &NodeClass::topicCallbackJointControllerStates, this);
00196 
00197                         // diagnostics
00198                         updater_.setHardwareID(ros::this_node::getName());
00199                         updater_.add("initialization", this, &NodeClass::diag_init);
00200             
00201             //set up timer to cyclically call controller-step
00202             timer_ctrl_step_ = n.createTimer(ros::Duration(sample_time_), &NodeClass::timerCallbackCtrlStep, this);
00203 
00204         }
00205         
00206         // Destructor
00207         ~NodeClass() 
00208         {
00209         }
00210 
00211                 void diag_init(diagnostic_updater::DiagnosticStatusWrapper &stat)
00212                 {
00213                 if(is_initialized_bool_)
00214                         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "");
00215                 else
00216                         stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "");
00217                         stat.add("Initialized", is_initialized_bool_);
00218                 }
00219 
00220                 // Listen for Pltf Cmds
00221                 void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr& msg)
00222                 {
00223                         double vx_cmd_mms, vy_cmd_mms, w_cmd_rads;
00224 
00225                         iwatchdog_ = 0;                 
00226 
00227                         // controller expects velocities in mm/s, ROS works with SI-Units -> convert
00228                         // ToDo: rework Controller Class to work with SI-Units
00229                         vx_cmd_mms = msg->linear.x*1000.0;
00230                         vy_cmd_mms = msg->linear.y*1000.0;
00231                         w_cmd_rads = msg->angular.z;
00232 
00233                         // only process if controller is already initialized
00234                         if (is_initialized_bool_ && drive_chain_diagnostic_==diagnostic_status_lookup_.OK)
00235             {
00236                                 ROS_DEBUG("received new velocity command [cmdVelX=%3.5f,cmdVelY=%3.5f,cmdVelTh=%3.5f]", 
00237                                         msg->linear.x, msg->linear.y, msg->angular.z);
00238 
00239                                 // Set desired value for Plattform Velocity to UndercarriageCtrl (setpoint setting)
00240                                 ucar_ctrl_->SetDesiredPltfVelocity(vx_cmd_mms, vy_cmd_mms, w_cmd_rads, 0.0);
00241                                 // ToDo: last value (0.0) is not used anymore --> remove from interface
00242                         }
00243                         else
00244                         {       
00245                                 // Set desired value for Plattform Velocity to zero (setpoint setting)
00246                                 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00247                                 // ToDo: last value (0.0) is not used anymore --> remove from interface
00248                                 ROS_DEBUG("Forced platform-velocity cmds to zero");
00249                         }
00250                 }
00251 
00252                 // Listen for Emergency Stop
00253                 void topicCallbackEMStop(const cob_relayboard::EmergencyStopState::ConstPtr& msg)
00254                 {
00255                         int EM_state;
00256                         EM_state = msg->emergency_state;
00257 
00258                         if (EM_state == msg->EMFREE)
00259                         {
00260                                 // Reset EM flag in Ctrlr
00261                                 if (is_initialized_bool_) 
00262                                 {
00263                                         ucar_ctrl_->setEMStopActive(false);
00264                                         ROS_DEBUG("Undercarriage Controller EM-Stop released");
00265                                         // reset only done, when system initialized
00266                                         // -> allows to stop ctrlr during init, reset and shutdown
00267                                 }
00268                         }
00269                         else
00270                         {
00271                 ROS_DEBUG("Undercarriage Controller stopped due to EM-Stop");
00272 
00273                                 // Set desired value for Plattform Velocity to zero (setpoint setting)
00274                                 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00275                                 // ToDo: last value (0.0) is not used anymore --> remove from interface
00276                                 ROS_DEBUG("Forced platform-velocity cmds to zero");
00277                 
00278                                 // Set EM flag and stop Ctrlr
00279                                 ucar_ctrl_->setEMStopActive(true);
00280                         }
00281                 }
00282 
00283                 // Listens for status of underlying hardware (base drive chain)
00284                 void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr& msg)
00285                 {
00286                         pr2_controllers_msgs::JointTrajectoryControllerState joint_state_cmd;
00287 
00288                         // prepare joint_cmds for heartbeat (compose header)
00289                         joint_state_cmd.header.stamp = ros::Time::now();
00290                         //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
00291                         // ToDo: configure over Config-File (number of motors) and Msg
00292                         // assign right size to JointState data containers
00293                         //joint_state_cmd.set_name_size(m_iNumMotors);
00294                         joint_state_cmd.desired.positions.resize(m_iNumJoints);
00295                         joint_state_cmd.desired.velocities.resize(m_iNumJoints);            
00296                         //joint_state_cmd.desired.effort.resize(m_iNumJoints);
00297                         joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00298                         joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00299                         joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00300                         joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00301                         joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00302                         joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00303                         joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00304                         joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00305                         joint_state_cmd.joint_names.resize(m_iNumJoints);
00306                         
00307                         // compose jointcmds
00308                         for(int i=0; i<m_iNumJoints; i++)
00309                         {
00310                                 joint_state_cmd.desired.positions[i] = 0.0;
00311                                 joint_state_cmd.desired.velocities[i] = 0.0;
00312                                 //joint_state_cmd.desired.effort[i] = 0.0;
00313                         }
00314                         
00315                         // set status of underlying drive chain to member variable 
00316                         drive_chain_diagnostic_ = msg->level;
00317 
00318                         // if controller is already started up ...
00319                         if (is_initialized_bool_)
00320                         {
00321                                 // ... but underlying drive chain is not yet operating normal
00322                                 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00323                                 {
00324                                         // halt controller
00325                         ROS_DEBUG("drive chain not availlable: halt Controller");
00326 
00327                                         // Set EM flag to Ctrlr (resets internal states)
00328                                         ucar_ctrl_->setEMStopActive(true);
00329 
00330                                         // Set desired value for Plattform Velocity to zero (setpoint setting)
00331                                         ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00332                                         // ToDo: last value (0.0) is not used anymore --> remove from interface
00333                                         ROS_DEBUG("Forced platform-velocity cmds to zero");
00334                                         
00335                                         // if is not Initializing
00336                                         if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00337                                         {
00338                                                 // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
00339                                                 // this is already done in CalcControlStep
00340                                         }
00341                                 }
00342                         }
00343                         // ... while controller is not initialized send heartbeats to keep motors alive
00344                         else
00345                         {
00346                                 // ... as soon as base drive chain is initialized
00347                                 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00348                                 {
00349                                         // publish zero-vel. jointcmds to avoid Watchdogs stopping ctrlr
00350                                         topic_pub_controller_joint_command_.publish(joint_state_cmd);
00351                                 }
00352                         }
00353                 }
00354 
00355                 void topicCallbackJointControllerStates(const pr2_controllers_msgs::JointTrajectoryControllerState::ConstPtr& msg) {
00356                         int num_joints;
00357                         int iter_k, iter_j;
00358                         std::vector<double> drive_joint_ang_rad, drive_joint_vel_rads, drive_joint_effort_NM;
00359                         std::vector<double> steer_joint_ang_rad, steer_joint_vel_rads, steer_joint_effort_NM;
00360         
00361                         joint_state_odom_stamp_ = msg->header.stamp;
00362         
00363                         // copy configuration into vector classes
00364                         num_joints = msg->joint_names.size();
00365                         // drive joints
00366                         drive_joint_ang_rad.assign(m_iNumJoints, 0.0);
00367                         drive_joint_vel_rads.assign(m_iNumJoints, 0.0);
00368                         drive_joint_effort_NM.assign(m_iNumJoints, 0.0);
00369                         // steer joints
00370                         steer_joint_ang_rad.assign(m_iNumJoints, 0.0);
00371                         steer_joint_vel_rads.assign(m_iNumJoints, 0.0);
00372                         steer_joint_effort_NM.assign(m_iNumJoints, 0.0);
00373 
00374                         // init iterators
00375                         iter_k = 0;
00376                         iter_j = 0;
00377 
00378                         for(int i = 0; i < num_joints; i++)
00379                         {
00380                                 // associate inputs to according steer and drive joints
00381                                 // ToDo: specify this globally (Prms-File or config-File or via msg-def.)       
00382                                 if(msg->joint_names[i] ==  "fl_caster_r_wheel_joint")
00383                                 {
00384                                                 drive_joint_ang_rad[0] = msg->actual.positions[i]; 
00385                                                 drive_joint_vel_rads[0] = msg->actual.velocities[i];
00386                                                 //drive_joint_effort_NM[0] = msg->effort[i];
00387                                 }
00388                                 if(msg->joint_names[i] ==  "bl_caster_r_wheel_joint")
00389                                 {
00390                                                 drive_joint_ang_rad[1] = msg->actual.positions[i]; 
00391                                                 drive_joint_vel_rads[1] = msg->actual.velocities[i];
00392                                                 //drive_joint_effort_NM[1] = msg->effort[i];
00393                                 }
00394                                 if(msg->joint_names[i] ==  "br_caster_r_wheel_joint")
00395                                 {
00396                                                 drive_joint_ang_rad[2] = msg->actual.positions[i]; 
00397                                                 drive_joint_vel_rads[2] = msg->actual.velocities[i];
00398                                                 //drive_joint_effort_NM[2] = msg->effort[i];
00399                                 }
00400                                 if(msg->joint_names[i] ==  "fr_caster_r_wheel_joint")
00401                                 {
00402                                                 drive_joint_ang_rad[3] = msg->actual.positions[i]; 
00403                                                 drive_joint_vel_rads[3] = msg->actual.velocities[i];
00404                                                 //drive_joint_effort_NM[3] = msg->effort[i];
00405                                 }
00406                                 if(msg->joint_names[i] ==  "fl_caster_rotation_joint")
00407                                 {
00408                                                 steer_joint_ang_rad[0] = msg->actual.positions[i]; 
00409                                                 steer_joint_vel_rads[0] = msg->actual.velocities[i];
00410                                                 //steer_joint_effort_NM[0] = msg->effort[i];
00411                                 }
00412                                 if(msg->joint_names[i] ==  "bl_caster_rotation_joint")
00413                                 { 
00414                                                 steer_joint_ang_rad[1] = msg->actual.positions[i]; 
00415                                                 steer_joint_vel_rads[1] = msg->actual.velocities[i];
00416                                                 //steer_joint_effort_NM[1] = msg->effort[i];
00417                                 }
00418                                 if(msg->joint_names[i] ==  "br_caster_rotation_joint")
00419                                 {
00420                                                 steer_joint_ang_rad[2] = msg->actual.positions[i]; 
00421                                                 steer_joint_vel_rads[2] = msg->actual.velocities[i];
00422                                                 //steer_joint_effort_NM[2] = msg->effort[i];
00423                                 }
00424                                 if(msg->joint_names[i] ==  "fr_caster_rotation_joint")
00425                                 {
00426                                                 steer_joint_ang_rad[3] = msg->actual.positions[i]; 
00427                                                 steer_joint_vel_rads[3] = msg->actual.velocities[i];
00428                                                 //steer_joint_effort_NM[3] = msg->effort[i];
00429                                 }
00430                         }
00431 
00432                         // Set measured Wheel Velocities and Angles to Controler Class (implements inverse kinematic)
00433                         ucar_ctrl_->SetActualWheelValues(drive_joint_vel_rads, steer_joint_vel_rads,
00434                                                                         drive_joint_ang_rad, steer_joint_ang_rad);
00435 
00436 
00437                         // calculate odometry every time
00438                         UpdateOdometry();
00439                         
00440                 }
00441                 
00442                 void timerCallbackCtrlStep(const ros::TimerEvent& e) {
00443                         CalcCtrlStep();
00444                 }
00445                 
00446         // other function declarations
00447                 // Initializes controller
00448         bool InitCtrl();
00449                 // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
00450                 void CalcCtrlStep();
00451                 // acquires the current undercarriage configuration from base_drive_chain
00452                 // calculates odometry from current measurement values and publishes it via an odometry topic and the tf broadcaster
00453                 void UpdateOdometry();
00454 };
00455 
00456 //#######################
00457 //#### main programm ####
00458 int main(int argc, char** argv)
00459 {
00460     // initialize ROS, spezify name of node
00461     ros::init(argc, argv, "undercarriage_ctrl");
00462     
00463         // construct nodeClass
00464     NodeClass nodeClass;
00465         
00466         // automatically do initializing of controller, because it's not directly depending any hardware components
00467         nodeClass.ucar_ctrl_->InitUndercarriageCtrl();
00468         nodeClass.is_initialized_bool_ = true;
00469         
00470         if( nodeClass.is_initialized_bool_ ) {
00471                 nodeClass.last_time_ = ros::Time::now();
00472                 ROS_INFO("Undercarriage control successfully initialized.");
00473         } else {
00474                 ROS_FATAL("Undercarriage control initialization failed!");
00475                 throw std::runtime_error("Undercarriage control initialization failed, check ini-Files!");
00476         }
00477     
00478         /* 
00479         CALLBACKS being executed are:
00480                 - actual motor values -> calculating direct kinematics and doing odometry (topicCallbackJointControllerStates)
00481                 - timer callback -> calculate controller step at a rate of sample_time_ (timerCallbackCtrlStep)
00482                 - other topic callbacks (diagnostics, command, em_stop_state)
00483         */
00484     ros::spin();
00485 
00486     return 0;
00487 }
00488 
00489 //##################################
00490 //#### function implementations ####
00491 
00492 // perform one control step, calculate inverse kinematics and publish updated joint cmd's (if no EMStop occurred)
00493 void NodeClass::CalcCtrlStep()
00494 {
00495         double vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy;
00496         std::vector<double> drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad;
00497         pr2_controllers_msgs::JointTrajectoryControllerState joint_state_cmd;
00498         int j, k;
00499         iwatchdog_ += 1;        
00500 
00501         // if controller is initialized and underlying hardware is operating normal
00502         if (is_initialized_bool_) //&& (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK))
00503         {
00504                 // as soon as (but only as soon as) platform drive chain is initialized start to send velocity commands
00505                 // Note: topicCallbackDiagnostic checks whether drives are operating nominal.
00506                 //       -> if warning or errors are issued target velocity is set to zero
00507 
00508                 // perform one control step,
00509                 // get the resulting cmd's for the wheel velocities and -angles from the controller class
00510                 // and output the achievable pltf velocity-cmds (if velocity limits where exceeded)
00511                 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);
00512                 // ToDo: adapt interface of controller class --> remove last values (not used anymore)
00513 
00514                 // if drives not operating nominal -> force commands to zero
00515                 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00516                 {
00517                         steer_jointang_cmds_rad.assign(m_iNumJoints, 0.0);
00518                         steer_jointvel_cmds_rads.assign(m_iNumJoints, 0.0);
00519                 }
00520 
00521                 // convert variables to SI-Units
00522                 vx_cmd_ms = vx_cmd_ms/1000.0;
00523                 vy_cmd_ms = vy_cmd_ms/1000.0;
00524 
00525                 // compose jointcmds
00526                 // compose header
00527                 joint_state_cmd.header.stamp = ros::Time::now();
00528                 //joint_state_cmd.header.frame_id = frame_id; //Where to get this id from?
00529                 // ToDo: configure over Config-File (number of motors) and Msg
00530                 // assign right size to JointState data containers
00531                 //joint_state_cmd.set_name_size(m_iNumMotors);
00532                 joint_state_cmd.desired.positions.resize(m_iNumJoints);
00533                 joint_state_cmd.desired.velocities.resize(m_iNumJoints);            
00534                 //joint_state_cmd.effort.resize(m_iNumJoints);
00535                 joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00536                 joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00537                 joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00538                 joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00539                 joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00540                 joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00541                 joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00542                 joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00543                 joint_state_cmd.joint_names.resize(m_iNumJoints);
00544 
00545                 // compose data body
00546                 j = 0;
00547                 k = 0;
00548                 for(int i = 0; i<m_iNumJoints; i++)
00549                 {
00550                         if(iwatchdog_ < (int) std::floor(timeout_/sample_time_) )
00551                         {
00552                                 // for steering motors
00553                                 if( i == 1 || i == 3 || i == 5 || i == 7) // ToDo: specify this via the Msg
00554                                 {
00555                                         joint_state_cmd.desired.positions[i] = steer_jointang_cmds_rad[j];
00556                                         joint_state_cmd.desired.velocities[i] = steer_jointvel_cmds_rads[j];
00557                                         //joint_state_cmd.effort[i] = 0.0;
00558                                         j = j + 1;
00559                                 }
00560                                 else
00561                                 {
00562                                         joint_state_cmd.desired.positions[i] = 0.0;
00563                                         joint_state_cmd.desired.velocities[i] = drive_jointvel_cmds_rads[k];
00564                                         //joint_state_cmd.effort[i] = 0.0;
00565                                         k = k + 1;
00566                                 }
00567                         }
00568                         else
00569                         {
00570                         joint_state_cmd.desired.positions[i] = 0.0;
00571                                 joint_state_cmd.desired.velocities[i] = 0.0;
00572                                 //joint_state_cmd.effort[i] = 0.0;
00573                         }
00574                 }
00575 
00576                 // publish jointcmds
00577                 topic_pub_controller_joint_command_.publish(joint_state_cmd);
00578                 }
00579 
00580 }
00581 
00582 // calculates odometry from current measurement values
00583 // and publishes it via an odometry topic and the tf broadcaster
00584 void NodeClass::UpdateOdometry()
00585 {
00586         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;
00587         double dummy1, dummy2;
00588         double dt;
00589         ros::Time current_time;
00590 
00591         // if drive chain already initialized process joint data
00592         //if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00593         if (is_initialized_bool_)
00594         {
00595                 // Get resulting Pltf Velocities from Ctrl-Class (result of forward kinematics)
00596                 // !Careful! Controller internally calculates with mm instead of m
00597                 // ToDo: change internal calculation to SI-Units
00598                 // ToDo: last values are not used anymore --> remove from interface
00599                 ucar_ctrl_->GetActualPltfVelocity(delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad, dummy1,
00600                                                                         vel_x_rob_ms, vel_y_rob_ms, rot_rob_rads, dummy2);
00601                 
00602                 // convert variables to SI-Units
00603                 vel_x_rob_ms = vel_x_rob_ms/1000.0;
00604                 vel_y_rob_ms = vel_y_rob_ms/1000.0;
00605                 delta_x_rob_m = delta_x_rob_m/1000.0;
00606                 delta_y_rob_m = delta_y_rob_m/1000.0;
00607                 
00608                 ROS_DEBUG("Odmonetry delta is: x=%f, y=%f, th=%f", delta_x_rob_m, delta_y_rob_m, rot_rob_rads);
00609         }
00610         else
00611         {
00612                 // otherwise set data (velocity and pose-delta) to zero
00613                 vel_x_rob_ms = 0.0;
00614                 vel_y_rob_ms = 0.0;
00615                 delta_x_rob_m = 0.0;
00616                 delta_y_rob_m = 0.0;
00617         }
00618 
00619         // calc odometry (from startup)
00620         // get time since last odometry-measurement
00621         current_time = ros::Time::now();
00622         dt = current_time.toSec() - last_time_.toSec();
00623         last_time_ = current_time;
00624         vel_rob_ms = sqrt(vel_x_rob_ms*vel_x_rob_ms + vel_y_rob_ms*vel_y_rob_ms);
00625 
00626         // calculation from ROS odom publisher tutorial http://www.ros.org/wiki/navigation/Tutorials/RobotSetup/Odom, using now midpoint integration
00627         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;
00628         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;
00629         theta_rob_rad_ = theta_rob_rad_ + rot_rob_rads * dt;
00630         //theta_rob_rad_ = theta_rob_rad_ + (rot_rob_rads+vel_theta_rob_last_)/2.0 * dt;
00631         
00632         vel_x_rob_last_ = vel_x_rob_ms;
00633         vel_y_rob_last_ = vel_y_rob_ms;
00634         vel_theta_rob_last_ = rot_rob_rads;
00635 
00636 
00637         // format data for compatibility with tf-package and standard odometry msg
00638         // generate quaternion for rotation
00639         geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00640 
00641         // compose and publish transform for tf package
00642         geometry_msgs::TransformStamped odom_tf;
00643         // compose header
00644         odom_tf.header.stamp = joint_state_odom_stamp_;
00645         odom_tf.header.frame_id = "/odom_combined";
00646         odom_tf.child_frame_id = "/base_footprint";
00647         // compose data container
00648         odom_tf.transform.translation.x = x_rob_m_;
00649         odom_tf.transform.translation.y = y_rob_m_;
00650         odom_tf.transform.translation.z = 0.0;
00651         odom_tf.transform.rotation = odom_quat;
00652 
00653     // compose and publish odometry message as topic
00654     nav_msgs::Odometry odom_top;
00655         // compose header
00656     odom_top.header.stamp = joint_state_odom_stamp_;
00657     odom_top.header.frame_id = "/wheelodom";
00658     odom_top.child_frame_id = "/base_footprint";
00659     // compose pose of robot
00660     odom_top.pose.pose.position.x = x_rob_m_;
00661     odom_top.pose.pose.position.y = y_rob_m_;
00662     odom_top.pose.pose.position.z = 0.0;
00663     odom_top.pose.pose.orientation = odom_quat;
00664     for(int i = 0; i < 6; i++)
00665       odom_top.pose.covariance[i*6+i] = 0.1;
00666 
00667     // compose twist of robot
00668     odom_top.twist.twist.linear.x = vel_x_rob_ms;
00669     odom_top.twist.twist.linear.y = vel_y_rob_ms;
00670     odom_top.twist.twist.linear.z = 0.0;
00671     odom_top.twist.twist.angular.x = 0.0;
00672     odom_top.twist.twist.angular.y = 0.0;
00673     odom_top.twist.twist.angular.z = rot_rob_rads;
00674     for(int i = 0; i < 6; i++)
00675       odom_top.twist.covariance[6*i+i] = 0.1;
00676 
00677         // publish the transform (for debugging, conflicts with robot-pose-ekf)
00678         tf_broadcast_odometry_.sendTransform(odom_tf);
00679         
00680         // publish odometry msg
00681         topic_pub_odometry_.publish(odom_top);
00682 }
00683 
00684 
00685 
00686 


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Sun Oct 5 2014 23:06:53