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 #include <ros/ros.h>
00026
00027
00028 #include <std_msgs/Float64.h>
00029 #include <sensor_msgs/JointState.h>
00030 #include <diagnostic_msgs/DiagnosticStatus.h>
00031 #include <diagnostic_msgs/DiagnosticArray.h>
00032 #include <control_msgs/JointTrajectoryControllerState.h>
00033 #include <control_msgs/JointControllerState.h>
00034
00035
00036 #include <std_srvs/Trigger.h>
00037 #include <cob_base_drive_chain/ElmoRecorderReadout.h>
00038 #include <cob_base_drive_chain/ElmoRecorderConfig.h>
00039
00040
00041
00042 #include <cob_base_drive_chain/CanCtrlPltfCOb3.h>
00043 #include <cob_utilities/IniFile.h>
00044 #include <cob_utilities/MathSup.h>
00045
00046
00047
00051 class NodeClass
00052 {
00053 public:
00054
00055 ros::NodeHandle n;
00056
00057
00061 ros::Publisher topicPub_JointState;
00062
00063 ros::Publisher topicPub_ControllerState;
00064 ros::Publisher topicPub_DiagnosticGlobal_;
00065
00066
00070 ros::Publisher topicPub_Diagnostic;
00071
00075 ros::Timer glDiagnostics_timer;
00076
00077
00081 ros::Subscriber topicSub_JointStateCmd;
00082
00083
00087 ros::ServiceServer srvServer_Init;
00088
00092 ros::ServiceServer srvServer_Recover;
00093
00097 ros::ServiceServer srvServer_Shutdown;
00098
00099 ros::ServiceServer srvServer_SetMotionType;
00100
00106 ros::ServiceServer srvServer_ElmoRecorderConfig;
00107
00122 ros::ServiceServer srvServer_ElmoRecorderReadout;
00123
00124
00125
00126
00127 #ifdef __SIM__
00128 ros::Publisher br_steer_pub;
00129 ros::Publisher bl_steer_pub;
00130 ros::Publisher fr_steer_pub;
00131 ros::Publisher fl_steer_pub;
00132 ros::Publisher br_caster_pub;
00133 ros::Publisher bl_caster_pub;
00134 ros::Publisher fr_caster_pub;
00135 ros::Publisher fl_caster_pub;
00136
00137 std::vector<double> m_gazeboPos;
00138 std::vector<double> m_gazeboVel;
00139 ros::Time m_gazeboStamp;
00140
00141 ros::Subscriber topicSub_GazeboJointStates;
00142 #else
00143 CanCtrlPltfCOb3 *m_CanCtrlPltf;
00144 #endif
00145 bool m_bisInitialized;
00146 int m_iNumMotors;
00147 int m_iNumDrives;
00148
00149 struct ParamType
00150 {
00151 double dMaxDriveRateRadpS;
00152 double dMaxSteerRateRadpS;
00153
00154 std::vector<double> vdWheelNtrlPosRad;
00155 };
00156 ParamType m_Param;
00157
00158 std::string sIniDirectory;
00159 bool m_bPubEffort;
00160 bool m_bReadoutElmo;
00161
00162
00163 NodeClass()
00164 {
00166
00167 if (n.hasParam("IniDirectory"))
00168 {
00169 n.getParam("IniDirectory", sIniDirectory);
00170 ROS_INFO("IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
00171 }
00172 else
00173 {
00174 sIniDirectory = "Platform/IniFiles/";
00175 ROS_WARN("IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
00176 }
00177
00178 n.param<bool>("PublishEffort", m_bPubEffort, false);
00179 if(m_bPubEffort) ROS_INFO("You have choosen to publish effort of motors, that charges capacity of CAN");
00180
00181
00182 IniFile iniFile;
00183 iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
00184
00185
00186 iniFile.GetKeyInt("Config", "NumberOfMotors", &m_iNumMotors, true);
00187 iniFile.GetKeyInt("Config", "NumberOfWheels", &m_iNumDrives, true);
00188 if(m_iNumMotors < 2 || m_iNumMotors > 8) {
00189 m_iNumMotors = 8;
00190 m_iNumDrives = 4;
00191 }
00192
00193 #ifdef __SIM__
00194 bl_caster_pub = n.advertise<std_msgs::Float64>("/base_bl_caster_r_wheel_controller/command", 1);
00195 br_caster_pub = n.advertise<std_msgs::Float64>("/base_br_caster_r_wheel_controller/command", 1);
00196 fl_caster_pub = n.advertise<std_msgs::Float64>("/base_fl_caster_r_wheel_controller/command", 1);
00197 fr_caster_pub = n.advertise<std_msgs::Float64>("/base_fr_caster_r_wheel_controller/command", 1);
00198 bl_steer_pub = n.advertise<std_msgs::Float64>("/base_bl_caster_rotation_controller/command", 1);
00199 br_steer_pub = n.advertise<std_msgs::Float64>("/base_br_caster_rotation_controller/command", 1);
00200 fl_steer_pub = n.advertise<std_msgs::Float64>("/base_fl_caster_rotation_controller/command", 1);
00201 fr_steer_pub = n.advertise<std_msgs::Float64>("/base_fr_caster_rotation_controller/command", 1);
00202
00203 topicSub_GazeboJointStates = n.subscribe("/joint_states", 1, &NodeClass::gazebo_joint_states_Callback, this);
00204
00205 m_gazeboPos.resize(m_iNumMotors);
00206 m_gazeboVel.resize(m_iNumMotors);
00207 #else
00208 topicPub_JointState = n.advertise<sensor_msgs::JointState>("/joint_states", 1);
00209 m_CanCtrlPltf = new CanCtrlPltfCOb3(sIniDirectory);
00210 #endif
00211
00212
00213
00214 topicPub_ControllerState = n.advertise<control_msgs::JointTrajectoryControllerState>("state", 1);
00215 topicPub_DiagnosticGlobal_ = n.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00216
00217 topicPub_Diagnostic = n.advertise<diagnostic_msgs::DiagnosticStatus>("diagnostic", 1);
00218
00219 topicSub_JointStateCmd = n.subscribe("joint_command", 1, &NodeClass::topicCallback_JointStateCmd, this);
00220
00221
00222 srvServer_Init = n.advertiseService("init", &NodeClass::srvCallback_Init, this);
00223 srvServer_ElmoRecorderConfig = n.advertiseService("ElmoRecorderConfig", &NodeClass::srvCallback_ElmoRecorderConfig, this);
00224 srvServer_ElmoRecorderReadout = n.advertiseService("ElmoRecorderReadout", &NodeClass::srvCallback_ElmoRecorderReadout, this);
00225 m_bReadoutElmo = false;
00226
00227 srvServer_Recover = n.advertiseService("recover", &NodeClass::srvCallback_Recover, this);
00228 srvServer_Shutdown = n.advertiseService("shutdown", &NodeClass::srvCallback_Shutdown, this);
00229
00230
00231 glDiagnostics_timer = n.createTimer(ros::Duration(1), &NodeClass::publish_globalDiagnostics, this);
00232
00233
00234 #ifdef __SIM__
00235 m_bisInitialized = initDrives();
00236 #else
00237 m_bisInitialized = false;
00238 #endif
00239
00240 }
00241
00242
00243 ~NodeClass()
00244 {
00245 #ifdef __SIM__
00246
00247 #else
00248 m_CanCtrlPltf->shutdownPltf();
00249 #endif
00250 }
00251
00252
00253
00254 void topicCallback_JointStateCmd(const control_msgs::JointTrajectoryControllerState::ConstPtr& msg)
00255 {
00256 ROS_DEBUG("Topic Callback joint_command");
00257
00258 if(m_bisInitialized == true)
00259 {
00260 ROS_DEBUG("Topic Callback joint_command - Sending Commands to drives (initialized)");
00261 sensor_msgs::JointState JointStateCmd;
00262 JointStateCmd.position.resize(m_iNumMotors);
00263 JointStateCmd.velocity.resize(m_iNumMotors);
00264 JointStateCmd.effort.resize(m_iNumMotors);
00265
00266 for(unsigned int i = 0; i < msg->joint_names.size(); i++)
00267 {
00268
00269
00270
00271
00272
00273 if(msg->joint_names[i] == "fl_caster_r_wheel_joint")
00274 {
00275 JointStateCmd.position[0] = msg->desired.positions[i];
00276 JointStateCmd.velocity[0] = msg->desired.velocities[i];
00277
00278 }
00279 else if(m_iNumDrives>=2 && msg->joint_names[i] == "bl_caster_r_wheel_joint")
00280 {
00281 JointStateCmd.position[2] = msg->desired.positions[i];
00282 JointStateCmd.velocity[2] = msg->desired.velocities[i];
00283
00284 }
00285 else if(m_iNumDrives>=3 && msg->joint_names[i] == "br_caster_r_wheel_joint")
00286 {
00287 JointStateCmd.position[4] = msg->desired.positions[i];
00288 JointStateCmd.velocity[4] = msg->desired.velocities[i];
00289
00290 }
00291 else if(m_iNumDrives>=4 && msg->joint_names[i] == "fr_caster_r_wheel_joint")
00292 {
00293 JointStateCmd.position[6] = msg->desired.positions[i];
00294 JointStateCmd.velocity[6] = msg->desired.velocities[i];
00295
00296 }
00297
00298 else if(msg->joint_names[i] == "fl_caster_rotation_joint")
00299 {
00300 JointStateCmd.position[1] = msg->desired.positions[i];
00301 JointStateCmd.velocity[1] = msg->desired.velocities[i];
00302
00303 }
00304 else if(m_iNumDrives>=2 && msg->joint_names[i] == "bl_caster_rotation_joint")
00305 {
00306 JointStateCmd.position[3] = msg->desired.positions[i];
00307 JointStateCmd.velocity[3] = msg->desired.velocities[i];
00308
00309 }
00310 else if(m_iNumDrives>=3 && msg->joint_names[i] == "br_caster_rotation_joint")
00311 {
00312 JointStateCmd.position[5] = msg->desired.positions[i];
00313 JointStateCmd.velocity[5] = msg->desired.velocities[i];
00314
00315 }
00316 else if(m_iNumDrives>=4 && msg->joint_names[i] == "fr_caster_rotation_joint")
00317 {
00318 JointStateCmd.position[7] = msg->desired.positions[i];
00319 JointStateCmd.velocity[7] = msg->desired.velocities[i];
00320
00321 }
00322 else
00323 {
00324 ROS_ERROR("Unkown joint name %s", (msg->joint_names[i]).c_str());
00325 }
00326 }
00327
00328
00329
00330 for(int i = 0; i < m_iNumMotors; i++)
00331 {
00332 #ifdef __SIM__
00333 #else
00334
00335 if( i == 1 || i == 3 || i == 5 || i == 7)
00336 {
00337 if (JointStateCmd.velocity[i] > m_Param.dMaxSteerRateRadpS)
00338 {
00339 JointStateCmd.velocity[i] = m_Param.dMaxSteerRateRadpS;
00340 }
00341 if (JointStateCmd.velocity[i] < -m_Param.dMaxSteerRateRadpS)
00342 {
00343 JointStateCmd.velocity[i] = -m_Param.dMaxSteerRateRadpS;
00344 }
00345 }
00346
00347 else
00348 {
00349 if (JointStateCmd.velocity[i] > m_Param.dMaxDriveRateRadpS)
00350 {
00351 JointStateCmd.velocity[i] = m_Param.dMaxDriveRateRadpS;
00352 }
00353 if (JointStateCmd.velocity[i] < -m_Param.dMaxDriveRateRadpS)
00354 {
00355 JointStateCmd.velocity[i] = -m_Param.dMaxDriveRateRadpS;
00356 }
00357 }
00358 #endif
00359 #ifdef __SIM__
00360 ROS_DEBUG("Send velocity data to gazebo");
00361 std_msgs::Float64 fl;
00362 fl.data = JointStateCmd.velocity[i];
00363 if(msg->joint_names[i] == "fl_caster_r_wheel_joint")
00364 fl_caster_pub.publish(fl);
00365 if(msg->joint_names[i] == "fr_caster_r_wheel_joint")
00366 fr_caster_pub.publish(fl);
00367 if(msg->joint_names[i] == "bl_caster_r_wheel_joint")
00368 bl_caster_pub.publish(fl);
00369 if(msg->joint_names[i] == "br_caster_r_wheel_joint")
00370 br_caster_pub.publish(fl);
00371
00372 if(msg->joint_names[i] == "fl_caster_rotation_joint")
00373 fl_steer_pub.publish(fl);
00374 if(msg->joint_names[i] == "fr_caster_rotation_joint")
00375 fr_steer_pub.publish(fl);
00376 if(msg->joint_names[i] == "bl_caster_rotation_joint")
00377 bl_steer_pub.publish(fl);
00378 if(msg->joint_names[i] == "br_caster_rotation_joint")
00379 br_steer_pub.publish(fl);
00380 ROS_DEBUG("Successfully sent velicities to gazebo");
00381 #else
00382 ROS_DEBUG("Send velocity data to drives");
00383 m_CanCtrlPltf->setVelGearRadS(i, JointStateCmd.velocity[i]);
00384 ROS_DEBUG("Successfully sent velicities to drives");
00385 #endif
00386 }
00387
00388 #ifdef __SIM__
00389
00390 #else
00391 if(m_bPubEffort) {
00392 m_CanCtrlPltf->requestMotorTorque();
00393 }
00394 #endif
00395 }
00396 }
00397
00398
00399
00400
00401
00402 bool srvCallback_Init(std_srvs::Trigger::Request &req,
00403 std_srvs::Trigger::Response &res )
00404 {
00405 ROS_DEBUG("Service callback init");
00406 if(m_bisInitialized == false)
00407 {
00408 m_bisInitialized = initDrives();
00409
00410
00411 res.success = m_bisInitialized;
00412 if(m_bisInitialized)
00413 {
00414 ROS_INFO("base initialized");
00415 }
00416 else
00417 {
00418 res.message = "initialization of base failed";
00419 ROS_ERROR("Initializing base failed");
00420 }
00421 }
00422 else
00423 {
00424 ROS_WARN("...base already initialized...");
00425 res.success = true;
00426 res.message = "platform already initialized";
00427 }
00428 return true;
00429 }
00430
00431 bool srvCallback_ElmoRecorderConfig(cob_base_drive_chain::ElmoRecorderConfig::Request &req,
00432 cob_base_drive_chain::ElmoRecorderConfig::Response &res ){
00433 if(m_bisInitialized)
00434 {
00435 #ifdef __SIM__
00436 res.success = true;
00437 #else
00438 m_CanCtrlPltf->evalCanBuffer();
00439 res.success = m_CanCtrlPltf->ElmoRecordings(0, req.recordinggap, "");
00440 #endif
00441 res.message = "Successfully configured all motors for instant record";
00442 }
00443
00444 return true;
00445 }
00446
00447 bool srvCallback_ElmoRecorderReadout(cob_base_drive_chain::ElmoRecorderReadout::Request &req,
00448 cob_base_drive_chain::ElmoRecorderReadout::Response &res ){
00449 if(m_bisInitialized) {
00450 #ifdef __SIM__
00451 res.success = true;
00452 #else
00453 m_CanCtrlPltf->evalCanBuffer();
00454 res.success = m_CanCtrlPltf->ElmoRecordings(1, req.subindex, req.fileprefix);
00455 #endif
00456 if(res.success == 0) {
00457 res.message = "Successfully requested reading out of Recorded data";
00458 m_bReadoutElmo = true;
00459 ROS_WARN("CPU consuming evalCanBuffer used for ElmoReadout activated");
00460 } else if(res.success == 1) res.message = "Recorder hasn't been configured well yet";
00461 else if(res.success == 2) res.message = "A previous transmission is still in progress";
00462 }
00463
00464 return true;
00465 }
00466
00467
00468
00469
00470 bool srvCallback_Recover(std_srvs::Trigger::Request &req,
00471 std_srvs::Trigger::Response &res )
00472 {
00473 if(m_bisInitialized)
00474 {
00475 ROS_DEBUG("Service callback recover");
00476 #ifdef __SIM__
00477 res.success = true;
00478 #else
00479 res.success = m_CanCtrlPltf->resetPltf();
00480 #endif
00481 if (res.success) {
00482 ROS_INFO("base resetted");
00483 } else {
00484 res.message = "reset of base failed";
00485 ROS_WARN("Resetting base failed");
00486 }
00487 }
00488 else
00489 {
00490 ROS_WARN("Base not yet initialized.");
00491 res.success = false;
00492 res.message = "Base not yet initialized.";
00493 }
00494 return true;
00495 }
00496
00497
00498 bool srvCallback_Shutdown(std_srvs::Trigger::Request &req,
00499 std_srvs::Trigger::Response &res )
00500 {
00501 ROS_DEBUG("Service callback shutdown");
00502 #ifdef __SIM__
00503 res.success = true;
00504 #else
00505 res.success = m_CanCtrlPltf->shutdownPltf();
00506 #endif
00507 if (res.success)
00508 ROS_INFO("Drives shut down");
00509 else
00510 ROS_INFO("Shutdown of Drives FAILED");
00511
00512 return true;
00513 }
00514
00515
00516 bool publish_JointStates()
00517 {
00518
00519 int j, k;
00520 bool bIsError;
00521 std::vector<double> vdAngGearRad, vdVelGearRad, vdEffortGearNM;
00522
00523
00524 vdAngGearRad.resize(m_iNumMotors, 0);
00525 vdVelGearRad.resize(m_iNumMotors, 0);
00526 vdEffortGearNM.resize(m_iNumMotors, 0);
00527
00528
00529 sensor_msgs::JointState jointstate;
00530 diagnostic_msgs::DiagnosticStatus diagnostics;
00531 control_msgs::JointTrajectoryControllerState controller_state;
00532
00533
00534 #ifdef __SIM__
00535 jointstate.header.stamp = m_gazeboStamp;
00536 controller_state.header.stamp = m_gazeboStamp;
00537 #else
00538 jointstate.header.stamp = ros::Time::now();
00539 controller_state.header.stamp = jointstate.header.stamp;
00540 #endif
00541
00542
00543
00544 jointstate.position.assign(m_iNumMotors, 0.0);
00545 jointstate.velocity.assign(m_iNumMotors, 0.0);
00546 jointstate.effort.assign(m_iNumMotors, 0.0);
00547
00548 if(m_bisInitialized == false)
00549 {
00550
00551 bIsError = false;
00552
00553 j = 0;
00554 k = 0;
00555
00556
00557 for(int i = 0; i<m_iNumMotors; i++)
00558 {
00559 jointstate.position[i] = 0.0;
00560 jointstate.velocity[i] = 0.0;
00561 jointstate.effort[i] = 0.0;
00562 }
00563 jointstate.name.push_back("fl_caster_r_wheel_joint");
00564 jointstate.name.push_back("fl_caster_rotation_joint");
00565 jointstate.name.push_back("bl_caster_r_wheel_joint");
00566 jointstate.name.push_back("bl_caster_rotation_joint");
00567 jointstate.name.push_back("br_caster_r_wheel_joint");
00568 jointstate.name.push_back("br_caster_rotation_joint");
00569 jointstate.name.push_back("fr_caster_r_wheel_joint");
00570 jointstate.name.push_back("fr_caster_rotation_joint");
00571 jointstate.name.resize(m_iNumMotors);
00572
00573 }
00574 else
00575 {
00576
00577
00578 #ifdef __SIM__
00579
00580 #else
00581 ROS_DEBUG("Read CAN-Buffer");
00582 m_CanCtrlPltf->evalCanBuffer();
00583 ROS_DEBUG("Successfully read CAN-Buffer");
00584 #endif
00585 j = 0;
00586 k = 0;
00587 for(int i = 0; i<m_iNumMotors; i++)
00588 {
00589 #ifdef __SIM__
00590 vdAngGearRad[i] = m_gazeboPos[i];
00591 vdVelGearRad[i] = m_gazeboVel[i];
00592 #else
00593 m_CanCtrlPltf->getGearPosVelRadS(i, &vdAngGearRad[i], &vdVelGearRad[i]);
00594 #endif
00595
00596
00597 if(m_bPubEffort) {
00598 for(int i=0; i<m_iNumMotors; i++)
00599 {
00600 #ifdef __SIM__
00601
00602 #else
00603 m_CanCtrlPltf->getMotorTorque(i, &vdEffortGearNM[i]);
00604 #endif
00605 }
00606 }
00607
00608
00609 if( i == 1 || i == 3 || i == 5 || i == 7)
00610 {
00611
00612 vdAngGearRad[i] += m_Param.vdWheelNtrlPosRad[j];
00613 MathSup::normalizePi(vdAngGearRad[i]);
00614 j = j+1;
00615 }
00616 }
00617
00618
00619 for(int i = 0; i<m_iNumMotors; i++)
00620 {
00621 jointstate.position[i] = vdAngGearRad[i];
00622 jointstate.velocity[i] = vdVelGearRad[i];
00623 jointstate.effort[i] = vdEffortGearNM[i];
00624 }
00625
00626 jointstate.name.push_back("fl_caster_r_wheel_joint");
00627 jointstate.name.push_back("fl_caster_rotation_joint");
00628 jointstate.name.push_back("bl_caster_r_wheel_joint");
00629 jointstate.name.push_back("bl_caster_rotation_joint");
00630 jointstate.name.push_back("br_caster_r_wheel_joint");
00631 jointstate.name.push_back("br_caster_rotation_joint");
00632 jointstate.name.push_back("fr_caster_r_wheel_joint");
00633 jointstate.name.push_back("fr_caster_rotation_joint");
00634 jointstate.name.resize(m_iNumMotors);
00635
00636 }
00637
00638 controller_state.joint_names = jointstate.name;
00639 controller_state.actual.positions = jointstate.position;
00640 controller_state.actual.velocities = jointstate.velocity;
00641
00642
00643 #ifdef __SIM__
00644
00645 #else
00646 topicPub_JointState.publish(jointstate);
00647 #endif
00648 topicPub_ControllerState.publish(controller_state);
00649
00650 ROS_DEBUG("published new drive-chain configuration (JointState message)");
00651
00652
00653 if(m_bisInitialized)
00654 {
00655
00656 #ifdef __SIM__
00657 bIsError = false;
00658 #else
00659 bIsError = m_CanCtrlPltf->isPltfError();
00660 #endif
00661 }
00662
00663
00664 if(bIsError)
00665 {
00666 diagnostics.level = 2;
00667 diagnostics.name = "drive-chain can node";
00668 diagnostics.message = "one or more drives are in Error mode";
00669 }
00670 else
00671 {
00672 if (m_bisInitialized)
00673 {
00674 diagnostics.level = 0;
00675 diagnostics.name = "drive-chain can node";
00676 diagnostics.message = "drives operating normal";
00677 }
00678 else
00679 {
00680 diagnostics.level = 1;
00681 diagnostics.name = "drive-chain can node";
00682 diagnostics.message = "drives are initializing";
00683 }
00684 }
00685
00686
00687 topicPub_Diagnostic.publish(diagnostics);
00688 ROS_DEBUG("published new drive-chain configuration (JointState message)");
00689
00690
00691 return true;
00692 }
00693
00694 void publish_globalDiagnostics(const ros::TimerEvent& event)
00695 {
00696
00697 diagnostic_msgs::DiagnosticArray diagnostics_gl;
00698 diagnostics_gl.header.stamp = ros::Time::now();
00699 diagnostics_gl.status.resize(1);
00700
00701 #ifdef __SIM__
00702 if (false)
00703 #else
00704 if(m_bisInitialized && m_CanCtrlPltf->isPltfError())
00705 #endif
00706
00707 {
00708 diagnostics_gl.status[0].level = 2;
00709 diagnostics_gl.status[0].name = ros::this_node::getName();
00710 diagnostics_gl.status[0].message = "Base not initialized or in error";
00711 }
00712 else
00713 {
00714 if (m_bisInitialized)
00715 {
00716 diagnostics_gl.status[0].level = 0;
00717 diagnostics_gl.status[0].name = ros::this_node::getName();
00718 diagnostics_gl.status[0].message = "base_drive_chain initialized and running";
00719 }
00720 else
00721 {
00722 diagnostics_gl.status[0].level = 1;
00723 diagnostics_gl.status[0].name = ros::this_node::getName();
00724 diagnostics_gl.status[0].message = "base_drive_chain not initialized";
00725 }
00726 }
00727
00728 topicPub_DiagnosticGlobal_.publish(diagnostics_gl);
00729 }
00730
00731
00732 bool initDrives();
00733
00734 #ifdef __SIM__
00735 void gazebo_joint_states_Callback(const sensor_msgs::JointState::ConstPtr& msg) {
00736 for (unsigned int i=0; i<msg->name.size(); i++) {
00737
00738 if(msg->name[i] == "fl_caster_r_wheel_joint") {
00739 m_gazeboPos[0] = msg->position[i];
00740 m_gazeboVel[0] = msg->velocity[i];
00741 m_gazeboStamp = msg->header.stamp;
00742 }
00743 else if(msg->name[i] == "bl_caster_r_wheel_joint") {
00744 m_gazeboPos[2] = msg->position[i];
00745 m_gazeboVel[2] = msg->velocity[i];
00746 }
00747 else if(msg->name[i] == "br_caster_r_wheel_joint") {
00748 m_gazeboPos[4] = msg->position[i];
00749 m_gazeboVel[4] = msg->velocity[i];
00750 }
00751 else if(msg->name[i] == "fr_caster_r_wheel_joint") {
00752 m_gazeboPos[6] = msg->position[i];
00753 m_gazeboVel[6] = msg->velocity[i];
00754 }
00755
00756
00757 else if(msg->name[i] == "fl_caster_rotation_joint") {
00758 m_gazeboPos[1] = msg->position[i];
00759 m_gazeboVel[1] = msg->velocity[i];
00760 }
00761 else if(msg->name[i] == "bl_caster_rotation_joint") {
00762 m_gazeboPos[3] = msg->position[i];
00763 m_gazeboVel[3] = msg->velocity[i];
00764 }
00765 else if(msg->name[i] == "br_caster_rotation_joint") {
00766 m_gazeboPos[5] = msg->position[i];
00767 m_gazeboVel[5] = msg->velocity[i];
00768 }
00769 else if(msg->name[i] == "fr_caster_rotation_joint") {
00770 m_gazeboPos[7] = msg->position[i];
00771 m_gazeboVel[7] = msg->velocity[i];
00772 }
00773 }
00774 }
00775 #else
00776
00777 #endif
00778 };
00779
00780
00781
00782 int main(int argc, char** argv)
00783 {
00784
00785 ros::init(argc, argv, "base_drive_chain");
00786
00787 NodeClass nodeClass;
00788
00789
00790 ros::Rate loop_rate(100);
00791
00792 while(nodeClass.n.ok())
00793 {
00794 #ifdef __SIM__
00795
00796 #else
00797
00798 if( nodeClass.m_bReadoutElmo )
00799 {
00800 if(nodeClass.m_bisInitialized) nodeClass.m_CanCtrlPltf->evalCanBuffer();
00801 if(nodeClass.m_CanCtrlPltf->ElmoRecordings(100, 0, "") == 0)
00802 {
00803 nodeClass.m_bReadoutElmo = false;
00804 ROS_INFO("CPU consuming evalCanBuffer used for ElmoReadout deactivated");
00805 }
00806 }
00807 #endif
00808
00809 nodeClass.publish_JointStates();
00810
00811 loop_rate.sleep();
00812 ros::spinOnce();
00813 }
00814
00815 return 0;
00816 }
00817
00818
00819
00820 bool NodeClass::initDrives()
00821 {
00822 ROS_INFO("Initializing Base Drive Chain");
00823
00824
00825 m_Param.vdWheelNtrlPosRad.assign((m_iNumDrives),0);
00826
00827
00828
00829 IniFile iniFile;
00830
00831
00832 iniFile.SetFileName(sIniDirectory + "Platform.ini", "PltfHardwareCoB3.h");
00833
00834
00835 iniFile.GetKeyDouble("DrivePrms", "MaxDriveRate", &m_Param.dMaxDriveRateRadpS, true);
00836 iniFile.GetKeyDouble("DrivePrms", "MaxSteerRate", &m_Param.dMaxSteerRateRadpS, true);
00837
00838 #ifdef __SIM__
00839
00840 if(m_iNumDrives >=1)
00841 m_Param.vdWheelNtrlPosRad[0] = 0.0f;
00842 if(m_iNumDrives >=2)
00843 m_Param.vdWheelNtrlPosRad[1] = 0.0f;
00844 if(m_iNumDrives >=3)
00845 m_Param.vdWheelNtrlPosRad[2] = 0.0f;
00846 if(m_iNumDrives >=4)
00847 m_Param.vdWheelNtrlPosRad[3] = 0.0f;
00848 #else
00849
00850 if(m_iNumDrives >=1)
00851 iniFile.GetKeyDouble("DrivePrms", "Wheel1NeutralPosition", &m_Param.vdWheelNtrlPosRad[0], true);
00852 if(m_iNumDrives >=2)
00853 iniFile.GetKeyDouble("DrivePrms", "Wheel2NeutralPosition", &m_Param.vdWheelNtrlPosRad[1], true);
00854 if(m_iNumDrives >=3)
00855 iniFile.GetKeyDouble("DrivePrms", "Wheel3NeutralPosition", &m_Param.vdWheelNtrlPosRad[2], true);
00856 if(m_iNumDrives >=4)
00857 iniFile.GetKeyDouble("DrivePrms", "Wheel4NeutralPosition", &m_Param.vdWheelNtrlPosRad[3], true);
00858
00859
00860 for(int i=0; i<m_iNumDrives; i++)
00861 {
00862 m_Param.vdWheelNtrlPosRad[i] = MathSup::convDegToRad(m_Param.vdWheelNtrlPosRad[i]);
00863 }
00864 #endif
00865
00866
00867 ROS_INFO("Initializing CanCtrlItf");
00868 bool bTemp1;
00869 #ifdef __SIM__
00870 bTemp1 = true;
00871 #else
00872 bTemp1 = m_CanCtrlPltf->initPltf();
00873 #endif
00874
00875 ROS_INFO("Initializing done");
00876
00877
00878 return bTemp1;
00879 }