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 <pr2_controllers_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 int drive_chain_diagnostic_;
00115 ros::Time last_time_;
00116 ros::Time joint_state_odom_stamp_;
00117 double sample_time_, timeout_;
00118 double x_rob_m_, y_rob_m_, theta_rob_rad_;
00119 int iwatchdog_;
00120 double vel_x_rob_last_, vel_y_rob_last_, vel_theta_rob_last_;
00121
00122 int m_iNumJoints;
00123
00124 diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_;
00125
00126
00127 NodeClass()
00128 {
00129
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
00141 drive_chain_diagnostic_ = diagnostic_status_lookup_.OK;
00142
00143
00144
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
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
00181
00182
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
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
00195 topic_sub_joint_controller_states_ = n.subscribe("state", 1, &NodeClass::topicCallbackJointControllerStates, this);
00196
00197
00198 updater_.setHardwareID(ros::this_node::getName());
00199 updater_.add("initialization", this, &NodeClass::diag_init);
00200
00201
00202 timer_ctrl_step_ = n.createTimer(ros::Duration(sample_time_), &NodeClass::timerCallbackCtrlStep, this);
00203
00204 }
00205
00206
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
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
00228
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
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
00240 ucar_ctrl_->SetDesiredPltfVelocity(vx_cmd_mms, vy_cmd_mms, w_cmd_rads, 0.0);
00241
00242 }
00243 else
00244 {
00245
00246 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00247
00248 ROS_DEBUG("Forced platform-velocity cmds to zero");
00249 }
00250 }
00251
00252
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
00261 if (is_initialized_bool_)
00262 {
00263 ucar_ctrl_->setEMStopActive(false);
00264 ROS_DEBUG("Undercarriage Controller EM-Stop released");
00265
00266
00267 }
00268 }
00269 else
00270 {
00271 ROS_DEBUG("Undercarriage Controller stopped due to EM-Stop");
00272
00273
00274 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00275
00276 ROS_DEBUG("Forced platform-velocity cmds to zero");
00277
00278
00279 ucar_ctrl_->setEMStopActive(true);
00280 }
00281 }
00282
00283
00284 void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr& msg)
00285 {
00286 pr2_controllers_msgs::JointTrajectoryControllerState joint_state_cmd;
00287
00288
00289 joint_state_cmd.header.stamp = ros::Time::now();
00290
00291
00292
00293
00294 joint_state_cmd.desired.positions.resize(m_iNumJoints);
00295 joint_state_cmd.desired.velocities.resize(m_iNumJoints);
00296
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
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
00313 }
00314
00315
00316 drive_chain_diagnostic_ = msg->level;
00317
00318
00319 if (is_initialized_bool_)
00320 {
00321
00322 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
00323 {
00324
00325 ROS_DEBUG("drive chain not availlable: halt Controller");
00326
00327
00328 ucar_ctrl_->setEMStopActive(true);
00329
00330
00331 ucar_ctrl_->SetDesiredPltfVelocity( 0.0, 0.0, 0.0, 0.0);
00332
00333 ROS_DEBUG("Forced platform-velocity cmds to zero");
00334
00335
00336 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00337 {
00338
00339
00340 }
00341 }
00342 }
00343
00344 else
00345 {
00346
00347 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
00348 {
00349
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
00364 num_joints = msg->joint_names.size();
00365
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
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
00375 iter_k = 0;
00376 iter_j = 0;
00377
00378 for(int i = 0; i < num_joints; i++)
00379 {
00380
00381
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
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
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
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
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
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
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
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
00429 }
00430 }
00431
00432
00433 ucar_ctrl_->SetActualWheelValues(drive_joint_vel_rads, steer_joint_vel_rads,
00434 drive_joint_ang_rad, steer_joint_ang_rad);
00435
00436
00437
00438 UpdateOdometry();
00439
00440 }
00441
00442 void timerCallbackCtrlStep(const ros::TimerEvent& e) {
00443 CalcCtrlStep();
00444 }
00445
00446
00447
00448 bool InitCtrl();
00449
00450 void CalcCtrlStep();
00451
00452
00453 void UpdateOdometry();
00454 };
00455
00456
00457
00458 int main(int argc, char** argv)
00459 {
00460
00461 ros::init(argc, argv, "undercarriage_ctrl");
00462
00463
00464 NodeClass nodeClass;
00465
00466
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
00480
00481
00482
00483
00484 ros::spin();
00485
00486 return 0;
00487 }
00488
00489
00490
00491
00492
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
00502 if (is_initialized_bool_)
00503 {
00504
00505
00506
00507
00508
00509
00510
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
00513
00514
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
00522 vx_cmd_ms = vx_cmd_ms/1000.0;
00523 vy_cmd_ms = vy_cmd_ms/1000.0;
00524
00525
00526
00527 joint_state_cmd.header.stamp = ros::Time::now();
00528
00529
00530
00531
00532 joint_state_cmd.desired.positions.resize(m_iNumJoints);
00533 joint_state_cmd.desired.velocities.resize(m_iNumJoints);
00534
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
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
00553 if( i == 1 || i == 3 || i == 5 || i == 7)
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
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
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
00573 }
00574 }
00575
00576
00577 topic_pub_controller_joint_command_.publish(joint_state_cmd);
00578 }
00579
00580 }
00581
00582
00583
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
00592
00593 if (is_initialized_bool_)
00594 {
00595
00596
00597
00598
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
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
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
00620
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
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
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
00638
00639 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_rob_rad_);
00640
00641
00642 geometry_msgs::TransformStamped odom_tf;
00643
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
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
00654 nav_msgs::Odometry odom_top;
00655
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
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
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
00678 tf_broadcast_odometry_.sendTransform(odom_tf);
00679
00680
00681 topic_pub_odometry_.publish(odom_top);
00682 }
00683
00684
00685
00686