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


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:32