00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060 #include <math.h>
00061
00062
00063 #include <ros/ros.h>
00064
00065
00066 #include <sensor_msgs/JointState.h>
00067 #include <diagnostic_msgs/DiagnosticStatus.h>
00068 #include <diagnostic_updater/diagnostic_updater.h>
00069 #include <geometry_msgs/Twist.h>
00070 #include <nav_msgs/Odometry.h>
00071 #include <tf/transform_broadcaster.h>
00072 #include <cob_relayboard/EmergencyStopState.h>
00073 #include <control_msgs/JointTrajectoryControllerState.h>
00074
00075
00076 #include <cob_undercarriage_ctrl/UndercarriageCtrlGeom.h>
00077 #include <cob_utilities/IniFile.h>
00078
00079
00080
00081
00082 class NodeClass
00083 {
00084
00085 public:
00086
00087 ros::NodeHandle n;
00088
00089
00090 ros::Publisher topic_pub_joint_state_cmd_;
00091 ros::Publisher topic_pub_controller_joint_command_;
00092 ros::Publisher topic_pub_odometry_;
00093 tf::TransformBroadcaster tf_broadcast_odometry_;
00094
00095
00096 ros::Subscriber topic_sub_CMD_pltf_twist_;
00097 ros::Subscriber topic_sub_EM_stop_state_;
00098 ros::Subscriber topic_sub_drive_diagnostic_;
00099
00100
00101
00102 ros::Subscriber topic_sub_joint_controller_states_;
00103
00104
00105 diagnostic_updater::Updater updater_;
00106
00107
00108 ros::Timer timer_ctrl_step_;
00109
00110
00111 UndercarriageCtrlGeom * ucar_ctrl_;
00112 std::string sIniDirectory;
00113 bool is_initialized_bool_;
00114 bool broadcast_tf_;
00115 int drive_chain_diagnostic_;
00116 ros::Time last_time_;
00117 ros::Time joint_state_odom_stamp_;
00118 double sample_time_, timeout_;
00119 double x_rob_m_, y_rob_m_, theta_rob_rad_;
00120 int iwatchdog_;
00121 double vel_x_rob_last_, vel_y_rob_last_, vel_theta_rob_last_;
00122 double max_vel_trans_, max_vel_rot_;
00123
00124 int m_iNumJoints;
00125
00126 diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_;
00127
00128
00129 NodeClass()
00130 {
00131
00132 is_initialized_bool_ = false;
00133 broadcast_tf_ = true;
00134 iwatchdog_ = 0;
00135 last_time_ = ros::Time::now();
00136 sample_time_ = 0.020;
00137 x_rob_m_ = 0.0;
00138 y_rob_m_ = 0.0;
00139 theta_rob_rad_ = 0.0;
00140 vel_x_rob_last_ = 0.0;
00141 vel_y_rob_last_ = 0.0;
00142 vel_theta_rob_last_ = 0.0;
00143
00144 drive_chain_diagnostic_ = diagnostic_status_lookup_.OK;
00145
00146
00147
00148 if (n.hasParam("timeout"))
00149 {
00150 n.getParam("timeout", timeout_);
00151 ROS_INFO("Timeout loaded from Parameter-Server is: %fs", timeout_);
00152 }
00153 else
00154 {
00155 ROS_WARN("No parameter timeout on Parameter-Server. Using default: 1.0s");
00156 timeout_ = 1.0;
00157 }
00158 if ( timeout_ < sample_time_ )
00159 {
00160 ROS_WARN("Specified timeout < sample_time. Setting timeout to sample_time = %fs", sample_time_);
00161 timeout_ = sample_time_;
00162 }
00163
00164
00165 if (n.hasParam("IniDirectory"))
00166 {
00167 n.getParam("IniDirectory", sIniDirectory);
00168 ROS_INFO("IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
00169 }
00170 else
00171 {
00172 sIniDirectory = "Platform/IniFiles/";
00173 ROS_WARN("IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
00174 }
00175
00176 if (n.hasParam("max_trans_velocity"))
00177 {
00178 n.getParam("max_trans_velocity", max_vel_trans_);
00179 ROS_INFO("Max translational velocity loaded from Parameter-Server is: %fs", max_vel_trans_);
00180 }
00181 else
00182 {
00183 ROS_WARN("No parameter max_trans_velocity on Parameter-Server. Using default: 1.1 m/s");
00184 max_vel_trans_ = 1.1;
00185 }
00186 if (n.hasParam("max_rot_velocity"))
00187 {
00188 n.getParam("max_rot_velocity", max_vel_rot_);
00189 ROS_INFO("Max rotational velocity loaded from Parameter-Server is: %fs", max_vel_rot_);
00190 }
00191 else
00192 {
00193 ROS_WARN("No parameter max_rot_velocity on Parameter-Server. Using default: 1.8 rad/s");
00194 max_vel_rot_ = 1.8;
00195 }
00196 if (n.hasParam("broadcast_tf"))
00197 {
00198 n.getParam("broadcast_tf", broadcast_tf_);
00199 }
00200
00201 IniFile iniFile;
00202 iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
00203 iniFile.GetKeyInt("Config", "NumberOfMotors", &m_iNumJoints, true);
00204
00205 ucar_ctrl_ = new UndercarriageCtrlGeom(sIniDirectory);
00206
00207
00208
00209
00210
00211 topic_pub_controller_joint_command_ = n.advertise<control_msgs::JointTrajectoryControllerState> ("joint_command", 1);
00212
00213 topic_pub_odometry_ = n.advertise<nav_msgs::Odometry>("odometry", 1);
00214
00215
00216 topic_sub_CMD_pltf_twist_ = n.subscribe("command", 1, &NodeClass::topicCallbackTwistCmd, this);
00217 topic_sub_EM_stop_state_ = n.subscribe("/emergency_stop_state", 1, &NodeClass::topicCallbackEMStop, this);
00218 topic_sub_drive_diagnostic_ = n.subscribe("diagnostic", 1, &NodeClass::topicCallbackDiagnostic, this);
00219
00220
00221
00222
00223 topic_sub_joint_controller_states_ = n.subscribe("state", 1, &NodeClass::topicCallbackJointControllerStates, this);
00224
00225
00226 updater_.setHardwareID(ros::this_node::getName());
00227 updater_.add("initialization", this, &NodeClass::diag_init);
00228
00229
00230 timer_ctrl_step_ = n.createTimer(ros::Duration(sample_time_), &NodeClass::timerCallbackCtrlStep, this);
00231
00232 }
00233
00234
00235 ~NodeClass()
00236 {
00237 }
00238
00239 void diag_init(diagnostic_updater::DiagnosticStatusWrapper &stat)
00240 {
00241 if(is_initialized_bool_)
00242 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "");
00243 else
00244 stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "");
00245 stat.add("Initialized", is_initialized_bool_);
00246 }
00247
00248
00249 void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr& msg)
00250 {
00251 double vx_cmd_mms, vy_cmd_mms, w_cmd_rads;
00252
00253 if( (fabs(msg->linear.x) > max_vel_trans_) || (fabs(msg->linear.y) > max_vel_trans_) || (fabs(msg->angular.z) > max_vel_rot_))
00254 {
00255 if(fabs(msg->linear.x) > max_vel_trans_)
00256 {
00257 ROS_DEBUG_STREAM("Recevied cmdVelX: " << msg->linear.x <<
00258 ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ << " so stop the robot");
00259 }
00260 if(fabs(msg->linear.y) > max_vel_trans_)
00261 {
00262 ROS_DEBUG_STREAM("Recevied cmdVelY: " << msg->linear.x <<
00263 ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ << " so stop the robot");
00264 }
00265
00266 if(fabs(msg->angular.z) > max_vel_rot_)
00267 {
00268 ROS_DEBUG_STREAM("Recevied cmdVelTh: " << msg->angular.z <<
00269 ", which is bigger than the maximal allowed rotational velocity: " << max_vel_rot_ << " so stop the robot");
00270 }
00271 vx_cmd_mms = 0.0;
00272 vy_cmd_mms = 0.0;
00273 w_cmd_rads = 0.0;
00274 }
00275 else
00276 {
00277
00278
00279 vx_cmd_mms = msg->linear.x*1000.0;
00280 vy_cmd_mms = msg->linear.y*1000.0;
00281 w_cmd_rads = msg->angular.z;
00282 }
00283
00284 iwatchdog_ = 0;
00285
00286
00287 if (is_initialized_bool_ && drive_chain_diagnostic_==diagnostic_status_lookup_.OK)
00288 {
00289 ROS_DEBUG("received new velocity command [cmdVelX=%3.5f,cmdVelY=%3.5f,cmdVelTh=%3.5f]",
00290 msg->linear.x, msg->linear.y, msg->angular.z);
00291
00292
00293 ucar_ctrl_->SetDesiredPltfVelocity(vx_cmd_mms, vy_cmd_mms, w_cmd_rads, 0.0);
00294
00295 }
00296 else
00297 {
00298
00299 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00300
00301 ROS_DEBUG("Forced platform-velocity cmds to zero");
00302 }
00303
00304 }
00305
00306
00307 void topicCallbackEMStop(const cob_relayboard::EmergencyStopState::ConstPtr& msg)
00308 {
00309 int EM_state;
00310 EM_state = msg->emergency_state;
00311
00312 if (EM_state == msg->EMFREE)
00313 {
00314
00315 if (is_initialized_bool_)
00316 {
00317 ucar_ctrl_->setEMStopActive(false);
00318 ROS_DEBUG("Undercarriage Controller EM-Stop released");
00319
00320
00321 }
00322 }
00323 else
00324 {
00325 ROS_DEBUG("Undercarriage Controller stopped due to EM-Stop");
00326
00327
00328 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00329
00330 ROS_DEBUG("Forced platform-velocity cmds to zero");
00331
00332
00333 ucar_ctrl_->setEMStopActive(true);
00334 }
00335 }
00336
00337
00338 void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr& msg)
00339 {
00340 control_msgs::JointTrajectoryControllerState joint_state_cmd;
00341
00342
00343 joint_state_cmd.header.stamp = ros::Time::now();
00344
00345
00346
00347
00348 joint_state_cmd.desired.positions.resize(m_iNumJoints);
00349 joint_state_cmd.desired.velocities.resize(m_iNumJoints);
00350
00351 joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00352 joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00353 joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00354 joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00355 joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00356 joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00357 joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00358 joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00359 joint_state_cmd.joint_names.resize(m_iNumJoints);
00360
00361
00362 for(int i=0; i<m_iNumJoints; i++)
00363 {
00364 joint_state_cmd.desired.positions[i] = 0.0;
00365 joint_state_cmd.desired.velocities[i] = 0.0;
00366
00367 }
00368
00369
00370 drive_chain_diagnostic_ = msg->level;
00371
00372
00373 if (is_initialized_bool_)
00374 {
00375
00376 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00377 {
00378
00379 ROS_DEBUG("drive chain not availlable: halt Controller");
00380
00381
00382 ucar_ctrl_->setEMStopActive(true);
00383
00384
00385 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00386
00387 ROS_DEBUG("Forced platform-velocity cmds to zero");
00388
00389
00390 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00391 {
00392
00393
00394 }
00395 }
00396 }
00397
00398 else
00399 {
00400
00401 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00402 {
00403
00404 topic_pub_controller_joint_command_.publish(joint_state_cmd);
00405 }
00406 }
00407 }
00408
00409 void topicCallbackJointControllerStates(const control_msgs::JointTrajectoryControllerState::ConstPtr& msg) {
00410 int num_joints;
00411 int iter_k, iter_j;
00412 std::vector<double> drive_joint_ang_rad, drive_joint_vel_rads, drive_joint_effort_NM;
00413 std::vector<double> steer_joint_ang_rad, steer_joint_vel_rads, steer_joint_effort_NM;
00414
00415 joint_state_odom_stamp_ = msg->header.stamp;
00416
00417
00418 num_joints = msg->joint_names.size();
00419
00420 drive_joint_ang_rad.assign(m_iNumJoints, 0.0);
00421 drive_joint_vel_rads.assign(m_iNumJoints, 0.0);
00422 drive_joint_effort_NM.assign(m_iNumJoints, 0.0);
00423
00424 steer_joint_ang_rad.assign(m_iNumJoints, 0.0);
00425 steer_joint_vel_rads.assign(m_iNumJoints, 0.0);
00426 steer_joint_effort_NM.assign(m_iNumJoints, 0.0);
00427
00428
00429 iter_k = 0;
00430 iter_j = 0;
00431
00432 for(int i = 0; i < num_joints; i++)
00433 {
00434
00435
00436 if(msg->joint_names[i] == "fl_caster_r_wheel_joint")
00437 {
00438 drive_joint_ang_rad[0] = msg->actual.positions[i];
00439 drive_joint_vel_rads[0] = msg->actual.velocities[i];
00440
00441 }
00442 if(msg->joint_names[i] == "bl_caster_r_wheel_joint")
00443 {
00444 drive_joint_ang_rad[1] = msg->actual.positions[i];
00445 drive_joint_vel_rads[1] = msg->actual.velocities[i];
00446
00447 }
00448 if(msg->joint_names[i] == "br_caster_r_wheel_joint")
00449 {
00450 drive_joint_ang_rad[2] = msg->actual.positions[i];
00451 drive_joint_vel_rads[2] = msg->actual.velocities[i];
00452
00453 }
00454 if(msg->joint_names[i] == "fr_caster_r_wheel_joint")
00455 {
00456 drive_joint_ang_rad[3] = msg->actual.positions[i];
00457 drive_joint_vel_rads[3] = msg->actual.velocities[i];
00458
00459 }
00460 if(msg->joint_names[i] == "fl_caster_rotation_joint")
00461 {
00462 steer_joint_ang_rad[0] = msg->actual.positions[i];
00463 steer_joint_vel_rads[0] = msg->actual.velocities[i];
00464
00465 }
00466 if(msg->joint_names[i] == "bl_caster_rotation_joint")
00467 {
00468 steer_joint_ang_rad[1] = msg->actual.positions[i];
00469 steer_joint_vel_rads[1] = msg->actual.velocities[i];
00470
00471 }
00472 if(msg->joint_names[i] == "br_caster_rotation_joint")
00473 {
00474 steer_joint_ang_rad[2] = msg->actual.positions[i];
00475 steer_joint_vel_rads[2] = msg->actual.velocities[i];
00476
00477 }
00478 if(msg->joint_names[i] == "fr_caster_rotation_joint")
00479 {
00480 steer_joint_ang_rad[3] = msg->actual.positions[i];
00481 steer_joint_vel_rads[3] = msg->actual.velocities[i];
00482
00483 }
00484 }
00485
00486
00487 ucar_ctrl_->SetActualWheelValues(drive_joint_vel_rads, steer_joint_vel_rads,
00488 drive_joint_ang_rad, steer_joint_ang_rad);
00489
00490
00491
00492 UpdateOdometry();
00493
00494 }
00495
00496 void timerCallbackCtrlStep(const ros::TimerEvent& e) {
00497 CalcCtrlStep();
00498 }
00499
00500
00501
00502 bool InitCtrl();
00503
00504 void CalcCtrlStep();
00505
00506
00507 void UpdateOdometry();
00508 };
00509
00510
00511
00512 int main(int argc, char** argv)
00513 {
00514
00515 ros::init(argc, argv, "undercarriage_ctrl");
00516
00517
00518 NodeClass nodeClass;
00519
00520
00521 nodeClass.ucar_ctrl_->InitUndercarriageCtrl();
00522 nodeClass.is_initialized_bool_ = true;
00523
00524 if( nodeClass.is_initialized_bool_ ) {
00525 nodeClass.last_time_ = ros::Time::now();
00526 ROS_INFO("Undercarriage control successfully initialized.");
00527 } else {
00528 ROS_FATAL("Undercarriage control initialization failed!");
00529 throw std::runtime_error("Undercarriage control initialization failed, check ini-Files!");
00530 }
00531
00532
00533
00534
00535
00536
00537
00538 ros::spin();
00539
00540 return 0;
00541 }
00542
00543
00544
00545
00546
00547 void NodeClass::CalcCtrlStep()
00548 {
00549 double vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy;
00550 std::vector<double> drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad;
00551 control_msgs::JointTrajectoryControllerState joint_state_cmd;
00552 int j, k;
00553 iwatchdog_ += 1;
00554
00555
00556 if (is_initialized_bool_)
00557 {
00558
00559
00560
00561
00562
00563
00564
00565 ucar_ctrl_->GetNewCtrlStateSteerDriveSetValues(drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad, vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy);
00566
00567
00568
00569 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00570 {
00571 steer_jointang_cmds_rad.assign(m_iNumJoints, 0.0);
00572 steer_jointvel_cmds_rads.assign(m_iNumJoints, 0.0);
00573 }
00574
00575
00576 vx_cmd_ms = vx_cmd_ms/1000.0;
00577 vy_cmd_ms = vy_cmd_ms/1000.0;
00578
00579
00580
00581 joint_state_cmd.header.stamp = ros::Time::now();
00582
00583
00584
00585
00586 joint_state_cmd.desired.positions.resize(m_iNumJoints);
00587 joint_state_cmd.desired.velocities.resize(m_iNumJoints);
00588
00589 joint_state_cmd.joint_names.push_back("fl_caster_r_wheel_joint");
00590 joint_state_cmd.joint_names.push_back("fl_caster_rotation_joint");
00591 joint_state_cmd.joint_names.push_back("bl_caster_r_wheel_joint");
00592 joint_state_cmd.joint_names.push_back("bl_caster_rotation_joint");
00593 joint_state_cmd.joint_names.push_back("br_caster_r_wheel_joint");
00594 joint_state_cmd.joint_names.push_back("br_caster_rotation_joint");
00595 joint_state_cmd.joint_names.push_back("fr_caster_r_wheel_joint");
00596 joint_state_cmd.joint_names.push_back("fr_caster_rotation_joint");
00597 joint_state_cmd.joint_names.resize(m_iNumJoints);
00598
00599
00600 j = 0;
00601 k = 0;
00602 for(int i = 0; i<m_iNumJoints; i++)
00603 {
00604 if(iwatchdog_ < (int) std::floor(timeout_/sample_time_) )
00605 {
00606
00607 if( i == 1 || i == 3 || i == 5 || i == 7)
00608 {
00609 joint_state_cmd.desired.positions[i] = steer_jointang_cmds_rad[j];
00610 joint_state_cmd.desired.velocities[i] = steer_jointvel_cmds_rads[j];
00611
00612 j = j + 1;
00613 }
00614 else
00615 {
00616 joint_state_cmd.desired.positions[i] = 0.0;
00617 joint_state_cmd.desired.velocities[i] = drive_jointvel_cmds_rads[k];
00618
00619 k = k + 1;
00620 }
00621 }
00622 else
00623 {
00624 joint_state_cmd.desired.positions[i] = 0.0;
00625 joint_state_cmd.desired.velocities[i] = 0.0;
00626
00627 }
00628 }
00629
00630
00631 topic_pub_controller_joint_command_.publish(joint_state_cmd);
00632 }
00633
00634 }
00635
00636
00637
00638 void NodeClass::UpdateOdometry()
00639 {
00640 double vel_x_rob_ms, vel_y_rob_ms, vel_rob_ms, rot_rob_rads, delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad;
00641 double dummy1, dummy2;
00642 double dt;
00643 ros::Time current_time;
00644
00645
00646
00647 if (is_initialized_bool_)
00648 {
00649
00650
00651
00652
00653 ucar_ctrl_->GetActualPltfVelocity(delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad, dummy1,
00654 vel_x_rob_ms, vel_y_rob_ms, rot_rob_rads, dummy2);
00655
00656
00657 vel_x_rob_ms = vel_x_rob_ms/1000.0;
00658 vel_y_rob_ms = vel_y_rob_ms/1000.0;
00659 delta_x_rob_m = delta_x_rob_m/1000.0;
00660 delta_y_rob_m = delta_y_rob_m/1000.0;
00661
00662 ROS_DEBUG("Odmonetry delta is: x=%f, y=%f, th=%f", delta_x_rob_m, delta_y_rob_m, rot_rob_rads);
00663 }
00664 else
00665 {
00666
00667 vel_x_rob_ms = 0.0;
00668 vel_y_rob_ms = 0.0;
00669 delta_x_rob_m = 0.0;
00670 delta_y_rob_m = 0.0;
00671 }
00672
00673
00674
00675 current_time = ros::Time::now();
00676 dt = current_time.toSec() - last_time_.toSec();
00677 last_time_ = current_time;
00678 vel_rob_ms = sqrt(vel_x_rob_ms*vel_x_rob_ms + vel_y_rob_ms*vel_y_rob_ms);
00679
00680
00681 x_rob_m_ = x_rob_m_ + ((vel_x_rob_ms+vel_x_rob_last_)/2.0 * cos(theta_rob_rad_) - (vel_y_rob_ms+vel_y_rob_last_)/2.0 * sin(theta_rob_rad_)) * dt;
00682 y_rob_m_ = y_rob_m_ + ((vel_x_rob_ms+vel_x_rob_last_)/2.0 * sin(theta_rob_rad_) + (vel_y_rob_ms+vel_y_rob_last_)/2.0 * cos(theta_rob_rad_)) * dt;
00683 theta_rob_rad_ = theta_rob_rad_ + rot_rob_rads * dt;
00684
00685
00686 vel_x_rob_last_ = vel_x_rob_ms;
00687 vel_y_rob_last_ = vel_y_rob_ms;
00688 vel_theta_rob_last_ = rot_rob_rads;
00689
00690
00691
00692
00693 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00694
00695 if (broadcast_tf_ == true)
00696 {
00697
00698 geometry_msgs::TransformStamped odom_tf;
00699
00700 odom_tf.header.stamp = joint_state_odom_stamp_;
00701 odom_tf.header.frame_id = "/odom_combined";
00702 odom_tf.child_frame_id = "/base_footprint";
00703
00704 odom_tf.transform.translation.x = x_rob_m_;
00705 odom_tf.transform.translation.y = y_rob_m_;
00706 odom_tf.transform.translation.z = 0.0;
00707 odom_tf.transform.rotation = odom_quat;
00708
00709
00710 tf_broadcast_odometry_.sendTransform(odom_tf);
00711 }
00712
00713
00714 nav_msgs::Odometry odom_top;
00715
00716 odom_top.header.stamp = joint_state_odom_stamp_;
00717 odom_top.header.frame_id = "/wheelodom";
00718 odom_top.child_frame_id = "/base_footprint";
00719
00720 odom_top.pose.pose.position.x = x_rob_m_;
00721 odom_top.pose.pose.position.y = y_rob_m_;
00722 odom_top.pose.pose.position.z = 0.0;
00723 odom_top.pose.pose.orientation = odom_quat;
00724 for(int i = 0; i < 6; i++)
00725 odom_top.pose.covariance[i*6+i] = 0.1;
00726
00727
00728 odom_top.twist.twist.linear.x = vel_x_rob_ms;
00729 odom_top.twist.twist.linear.y = vel_y_rob_ms;
00730 odom_top.twist.twist.linear.z = 0.0;
00731 odom_top.twist.twist.angular.x = 0.0;
00732 odom_top.twist.twist.angular.y = 0.0;
00733 odom_top.twist.twist.angular.z = rot_rob_rads;
00734 for(int i = 0; i < 6; i++)
00735 odom_top.twist.covariance[6*i+i] = 0.1;
00736
00737
00738 topic_pub_odometry_.publish(odom_top);
00739 }
00740
00741
00742
00743