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