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