00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <unistd.h>
00022 #include <map>
00023 #include <string>
00024 #include <vector>
00025
00026
00027 #include <ros/ros.h>
00028 #include <urdf/model.h>
00029 #include <actionlib/server/simple_action_server.h>
00030
00031
00032 #include <std_msgs/Float64MultiArray.h>
00033 #include <trajectory_msgs/JointTrajectory.h>
00034 #include <sensor_msgs/JointState.h>
00035 #include <control_msgs/FollowJointTrajectoryAction.h>
00036 #include <control_msgs/JointTrajectoryControllerState.h>
00037
00038
00039 #include <std_srvs/Trigger.h>
00040 #include <cob_srvs/SetString.h>
00041
00042
00043 #include <diagnostic_msgs/DiagnosticArray.h>
00044
00045
00046 #include <schunk_sdh/sdh.h>
00047
00053 class SdhNode
00054 {
00055 public:
00057 ros::NodeHandle nh_;
00058 ros::NodeHandle nh_private_;
00059
00060 private:
00061
00062 ros::Publisher topicPub_JointState_;
00063 ros::Publisher topicPub_ControllerState_;
00064 ros::Publisher topicPub_Diagnostics_;
00065
00066
00067 ros::Subscriber subSetVelocitiesRaw_;
00068
00069
00070 ros::ServiceServer srvServer_Init_;
00071 ros::ServiceServer srvServer_Stop_;
00072 ros::ServiceServer srvServer_Recover_;
00073 ros::ServiceServer srvServer_SetOperationMode_;
00074
00075
00076 actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> as_;
00077 std::string action_name_;
00078
00079
00080
00081
00082
00083 SDH::cSDH *sdh_;
00084 std::vector<SDH::cSDH::eAxisState> state_;
00085
00086 std::string sdhdevicetype_;
00087 std::string sdhdevicestring_;
00088 int sdhdevicenum_;
00089 int baudrate_, id_read_, id_write_;
00090 double timeout_;
00091
00092 bool isInitialized_;
00093 bool isError_;
00094 int DOF_;
00095 double pi_;
00096
00097 trajectory_msgs::JointTrajectory traj_;
00098
00099 std::vector<std::string> joint_names_;
00100 std::vector<int> axes_;
00101 std::vector<double> targetAngles_;
00102 std::vector<double> velocities_;
00103 bool hasNewGoal_;
00104 std::string operationMode_;
00105
00106 public:
00112 SdhNode() :
00113 as_(nh_, "joint_trajectory_controller/follow_joint_trajectory", boost::bind(&SdhNode::executeCB, this, _1), false), action_name_(
00114 "follow_joint_trajectory")
00115 {
00116 nh_private_ = ros::NodeHandle("~");
00117 pi_ = 3.1415926;
00118 isError_ = false;
00119
00120 as_.start();
00121 }
00122
00126 ~SdhNode()
00127 {
00128 if (isInitialized_)
00129 sdh_->Close();
00130 delete sdh_;
00131 }
00132
00136 bool init()
00137 {
00138
00139 isInitialized_ = false;
00140 hasNewGoal_ = false;
00141
00142
00143 topicPub_JointState_ = nh_.advertise<sensor_msgs::JointState>("joint_states", 1);
00144 topicPub_ControllerState_ = nh_.advertise<control_msgs::JointTrajectoryControllerState>(
00145 "joint_trajectory_controller/state", 1);
00146 topicPub_Diagnostics_ = nh_.advertise<diagnostic_msgs::DiagnosticArray>("diagnostics", 1);
00147
00148
00149 sdh_ = new SDH::cSDH(false, false, 0);
00150
00151
00152 srvServer_Init_ = nh_.advertiseService("driver/init", &SdhNode::srvCallback_Init, this);
00153 srvServer_Stop_ = nh_.advertiseService("driver/stop", &SdhNode::srvCallback_Stop, this);
00154 srvServer_Recover_ = nh_.advertiseService("driver/recover", &SdhNode::srvCallback_Init, this);
00155 srvServer_SetOperationMode_ = nh_.advertiseService("driver/set_operation_mode",
00156 &SdhNode::srvCallback_SetOperationMode, this);
00157
00158 subSetVelocitiesRaw_ = nh_.subscribe("joint_group_velocity_controller/command", 1,
00159 &SdhNode::topicCallback_setVelocitiesRaw, this);
00160
00161
00162 nh_private_.param("sdhdevicetype", sdhdevicetype_, std::string("PCAN"));
00163 nh_private_.param("sdhdevicestring", sdhdevicestring_, std::string("/dev/pcan0"));
00164 nh_private_.param("sdhdevicenum", sdhdevicenum_, 0);
00165
00166 nh_private_.param("baudrate", baudrate_, 1000000);
00167 nh_private_.param("timeout", timeout_, static_cast<double>(0.04));
00168 nh_private_.param("id_read", id_read_, 43);
00169 nh_private_.param("id_write", id_write_, 42);
00170
00171
00172 ROS_INFO("getting joint_names from parameter server");
00173 XmlRpc::XmlRpcValue joint_names_param;
00174 if (nh_private_.hasParam("joint_names"))
00175 {
00176 nh_private_.getParam("joint_names", joint_names_param);
00177 }
00178 else
00179 {
00180 ROS_ERROR("Parameter 'joint_names' not set, shutting down node...");
00181 nh_.shutdown();
00182 return false;
00183 }
00184 DOF_ = joint_names_param.size();
00185 joint_names_.resize(DOF_);
00186 for (int i = 0; i < DOF_; i++)
00187 {
00188 joint_names_[i] = (std::string)joint_names_param[i];
00189 }
00190 std::cout << "joint_names = " << joint_names_param << std::endl;
00191
00192
00193 axes_.resize(DOF_);
00194 velocities_.resize(DOF_);
00195 for (int i = 0; i < DOF_; i++)
00196 {
00197 axes_[i] = i;
00198 }
00199 ROS_INFO("DOF = %d", DOF_);
00200
00201 state_.resize(axes_.size());
00202
00203 nh_private_.param("OperationMode", operationMode_, std::string("position"));
00204 return true;
00205 }
00211 bool switchOperationMode(const std::string &mode)
00212 {
00213 hasNewGoal_ = false;
00214 sdh_->Stop();
00215
00216 try
00217 {
00218 if (mode == "position")
00219 {
00220 sdh_->SetController(SDH::cSDH::eCT_POSE);
00221 }
00222 else if (mode == "velocity")
00223 {
00224 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
00225 }
00226 else
00227 {
00228 ROS_ERROR_STREAM("Operation mode '" << mode << "' not supported");
00229 return false;
00230 }
00231 sdh_->SetAxisEnable(sdh_->All, 1.0);
00232 }
00233 catch (SDH::cSDHLibraryException* e)
00234 {
00235 ROS_ERROR("An exception was caught: %s", e->what());
00236 delete e;
00237 return false;
00238 }
00239
00240 operationMode_ = mode;
00241 return true;
00242 }
00243
00250 void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
00251 {
00252 ROS_INFO("sdh: executeCB");
00253 if (operationMode_ != "position")
00254 {
00255 ROS_ERROR("%s: Rejected, sdh not in position mode", action_name_.c_str());
00256 as_.setAborted();
00257 return;
00258 }
00259 if (!isInitialized_)
00260 {
00261 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00262 as_.setAborted();
00263 return;
00264 }
00265
00266 if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() != size_t(DOF_))
00267 {
00268 ROS_ERROR("%s: Rejected, malformed FollowJointTrajectoryGoal", action_name_.c_str());
00269 as_.setAborted();
00270 return;
00271 }
00272 while (hasNewGoal_ == true)
00273 usleep(10000);
00274
00275 std::map<std::string, int> dict;
00276 for (int idx = 0; idx < goal->trajectory.joint_names.size(); idx++)
00277 {
00278 dict[goal->trajectory.joint_names[idx]] = idx;
00279 }
00280
00281 targetAngles_.resize(DOF_);
00282 targetAngles_[0] = goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]] * 180.0 / pi_;
00283 targetAngles_[1] = goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]] * 180.0 / pi_;
00284 targetAngles_[2] = goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]] * 180.0 / pi_;
00285 targetAngles_[3] = goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]] * 180.0 / pi_;
00286 targetAngles_[4] = goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]] * 180.0 / pi_;
00287 targetAngles_[5] = goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]] * 180.0 / pi_;
00288 targetAngles_[6] = goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]] * 180.0 / pi_;
00289 ROS_INFO(
00290 "received position goal: [['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']] = [%f,%f,%f,%f,%f,%f,%f]",
00291 goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]],
00292 goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]],
00293 goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]],
00294 goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]],
00295 goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]],
00296 goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]],
00297 goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]]);
00298
00299 hasNewGoal_ = true;
00300
00301 usleep(500000);
00302
00303 bool finished = false;
00304 while (finished == false)
00305 {
00306 if (as_.isNewGoalAvailable())
00307 {
00308 ROS_WARN("%s: Aborted", action_name_.c_str());
00309 as_.setAborted();
00310 return;
00311 }
00312 for (unsigned int i = 0; i < state_.size(); i++)
00313 {
00314 ROS_DEBUG("state[%d] = %d", i, state_[i]);
00315 if (state_[i] == 0)
00316 {
00317 finished = true;
00318 }
00319 else
00320 {
00321 finished = false;
00322 }
00323 }
00324 usleep(10000);
00325 }
00326
00327
00328 ROS_INFO("%s: Succeeded", action_name_.c_str());
00329 as_.setSucceeded();
00330 }
00331
00332 void topicCallback_setVelocitiesRaw(const std_msgs::Float64MultiArrayPtr& velocities)
00333 {
00334 if (!isInitialized_)
00335 {
00336 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00337 return;
00338 }
00339 if (velocities->data.size() != velocities_.size())
00340 {
00341 ROS_ERROR("Velocity array dimension mismatch");
00342 return;
00343 }
00344 if (operationMode_ != "velocity")
00345 {
00346 ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
00347 return;
00348 }
00349
00350
00351 while (hasNewGoal_ == true)
00352 usleep(10000);
00353
00354 velocities_[0] = velocities->data[0] * 180.0 / pi_;
00355 velocities_[1] = velocities->data[5] * 180.0 / pi_;
00356 velocities_[2] = velocities->data[6] * 180.0 / pi_;
00357 velocities_[3] = velocities->data[1] * 180.0 / pi_;
00358 velocities_[4] = velocities->data[2] * 180.0 / pi_;
00359 velocities_[5] = velocities->data[3] * 180.0 / pi_;
00360 velocities_[6] = velocities->data[4] * 180.0 / pi_;
00361
00362 hasNewGoal_ = true;
00363 }
00364
00372 bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
00373 {
00374 if (isInitialized_ == false)
00375 {
00376
00377
00378 try
00379 {
00380 if (sdhdevicetype_.compare("RS232") == 0)
00381 {
00382 sdh_->OpenRS232(sdhdevicenum_, 115200, 1, sdhdevicestring_.c_str());
00383 ROS_INFO("Initialized RS232 for SDH");
00384 isInitialized_ = true;
00385 }
00386 if (sdhdevicetype_.compare("PCAN") == 0)
00387 {
00388 ROS_INFO("Starting initializing PEAKCAN");
00389 sdh_->OpenCAN_PEAK(baudrate_, timeout_, id_read_, id_write_, sdhdevicestring_.c_str());
00390 ROS_INFO("Initialized PEAK CAN for SDH");
00391 isInitialized_ = true;
00392 }
00393 if (sdhdevicetype_.compare("ESD") == 0)
00394 {
00395 ROS_INFO("Starting initializing ESD");
00396 if (strcmp(sdhdevicestring_.c_str(), "/dev/can0") == 0)
00397 {
00398 ROS_INFO("Initializing ESD on device %s", sdhdevicestring_.c_str());
00399 sdh_->OpenCAN_ESD(0, baudrate_, timeout_, id_read_, id_write_);
00400 }
00401 else if (strcmp(sdhdevicestring_.c_str(), "/dev/can1") == 0)
00402 {
00403 ROS_INFO("Initializin ESD on device %s", sdhdevicestring_.c_str());
00404 sdh_->OpenCAN_ESD(1, baudrate_, timeout_, id_read_, id_write_);
00405 }
00406 else
00407 {
00408 ROS_ERROR("Currently only support for /dev/can0 and /dev/can1");
00409 res.success = false;
00410 res.message = "Currently only support for /dev/can0 and /dev/can1";
00411 return true;
00412 }
00413 ROS_INFO("Initialized ESDCAN for SDH");
00414 isInitialized_ = true;
00415 }
00416 }
00417 catch (SDH::cSDHLibraryException* e)
00418 {
00419 ROS_ERROR("An exception was caught: %s", e->what());
00420 res.success = false;
00421 res.message = e->what();
00422 delete e;
00423 return true;
00424 }
00425 if (!switchOperationMode(operationMode_))
00426 {
00427 res.success = false;
00428 res.message = "Could not set operation mode to '" + operationMode_ + "'";
00429 return true;
00430 }
00431 }
00432 else
00433 {
00434 ROS_WARN("...sdh already initialized...");
00435 res.success = true;
00436 res.message = "sdh already initialized";
00437 }
00438
00439 res.success = true;
00440 return true;
00441 }
00442
00450 bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
00451 {
00452 ROS_INFO("Stopping sdh");
00453
00454
00455 try
00456 {
00457 sdh_->Stop();
00458 }
00459 catch (SDH::cSDHLibraryException* e)
00460 {
00461 ROS_ERROR("An exception was caught: %s", e->what());
00462 delete e;
00463 }
00464
00465 ROS_INFO("Stopping sdh succesfull");
00466 res.success = true;
00467 return true;
00468 }
00469
00477 bool srvCallback_Recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
00478 {
00479 ROS_WARN("Service recover not implemented yet");
00480 res.success = true;
00481 res.message = "Service recover not implemented yet";
00482 return true;
00483 }
00484
00492 bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
00493 {
00494 hasNewGoal_ = false;
00495 sdh_->Stop();
00496 res.success = switchOperationMode(req.data);
00497 if (operationMode_ == "position")
00498 {
00499 sdh_->SetController(SDH::cSDH::eCT_POSE);
00500 }
00501 else if (operationMode_ == "velocity")
00502 {
00503 try
00504 {
00505 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
00506 sdh_->SetAxisEnable(sdh_->All, 1.0);
00507 }
00508 catch (SDH::cSDHLibraryException* e)
00509 {
00510 ROS_ERROR("An exception was caught: %s", e->what());
00511 delete e;
00512 }
00513 }
00514 else
00515 {
00516 ROS_ERROR_STREAM("Operation mode '" << req.data << "' not supported");
00517 }
00518 return true;
00519 }
00520
00526 void updateSdh()
00527 {
00528 ROS_DEBUG("updateJointState");
00529 if (isInitialized_ == true)
00530 {
00531 if (hasNewGoal_ == true)
00532 {
00533
00534 try
00535 {
00536 sdh_->Stop();
00537 }
00538 catch (SDH::cSDHLibraryException* e)
00539 {
00540 ROS_ERROR("An exception was caught: %s", e->what());
00541 delete e;
00542 }
00543
00544 if (operationMode_ == "position")
00545 {
00546 ROS_DEBUG("moving sdh in position mode");
00547
00548 try
00549 {
00550 sdh_->SetAxisTargetAngle(axes_, targetAngles_);
00551 sdh_->MoveHand(false);
00552 }
00553 catch (SDH::cSDHLibraryException* e)
00554 {
00555 ROS_ERROR("An exception was caught: %s", e->what());
00556 delete e;
00557 }
00558 }
00559 else if (operationMode_ == "velocity")
00560 {
00561 ROS_DEBUG("moving sdh in velocity mode");
00562 try
00563 {
00564 sdh_->SetAxisTargetVelocity(axes_, velocities_);
00565
00566 }
00567 catch (SDH::cSDHLibraryException* e)
00568 {
00569 ROS_ERROR("An exception was caught: %s", e->what());
00570 delete e;
00571 }
00572 }
00573 else if (operationMode_ == "effort")
00574 {
00575 ROS_DEBUG("moving sdh in effort mode");
00576
00577 ROS_WARN("Moving in effort mode currently disabled");
00578 }
00579 else
00580 {
00581 ROS_ERROR("sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]",
00582 operationMode_.c_str());
00583 }
00584
00585 hasNewGoal_ = false;
00586 }
00587
00588
00589 std::vector<double> actualAngles;
00590 try
00591 {
00592 actualAngles = sdh_->GetAxisActualAngle(axes_);
00593 }
00594 catch (SDH::cSDHLibraryException* e)
00595 {
00596 ROS_ERROR("An exception was caught: %s", e->what());
00597 delete e;
00598 }
00599 std::vector<double> actualVelocities;
00600 try
00601 {
00602 actualVelocities = sdh_->GetAxisActualVelocity(axes_);
00603 }
00604 catch (SDH::cSDHLibraryException* e)
00605 {
00606 ROS_ERROR("An exception was caught: %s", e->what());
00607 delete e;
00608 }
00609
00610 ROS_DEBUG("received %d angles from sdh", static_cast<int>(actualAngles.size()));
00611
00612 ros::Time time = ros::Time::now();
00613
00614
00615 sensor_msgs::JointState msg;
00616 msg.header.stamp = time;
00617 msg.name.resize(DOF_);
00618 msg.position.resize(DOF_);
00619 msg.velocity.resize(DOF_);
00620 msg.effort.resize(DOF_);
00621
00622 msg.name = joint_names_;
00623
00624
00625 msg.position[0] = actualAngles[0] * pi_ / 180.0;
00626 msg.position[1] = actualAngles[3] * pi_ / 180.0;
00627 msg.position[2] = actualAngles[4] * pi_ / 180.0;
00628 msg.position[3] = actualAngles[5] * pi_ / 180.0;
00629 msg.position[4] = actualAngles[6] * pi_ / 180.0;
00630 msg.position[5] = actualAngles[1] * pi_ / 180.0;
00631 msg.position[6] = actualAngles[2] * pi_ / 180.0;
00632
00633 msg.velocity[0] = actualVelocities[0] * pi_ / 180.0;
00634 msg.velocity[1] = actualVelocities[3] * pi_ / 180.0;
00635 msg.velocity[2] = actualVelocities[4] * pi_ / 180.0;
00636 msg.velocity[3] = actualVelocities[5] * pi_ / 180.0;
00637 msg.velocity[4] = actualVelocities[6] * pi_ / 180.0;
00638 msg.velocity[5] = actualVelocities[1] * pi_ / 180.0;
00639 msg.velocity[6] = actualVelocities[2] * pi_ / 180.0;
00640
00641 topicPub_JointState_.publish(msg);
00642
00643
00644 sensor_msgs::JointState mimicjointmsg;
00645 mimicjointmsg.header.stamp = time;
00646 mimicjointmsg.name.resize(1);
00647 mimicjointmsg.position.resize(1);
00648 mimicjointmsg.velocity.resize(1);
00649 mimicjointmsg.name[0] = "sdh_finger_21_joint";
00650 mimicjointmsg.position[0] = msg.position[0];
00651 mimicjointmsg.velocity[0] = msg.velocity[0];
00652 topicPub_JointState_.publish(mimicjointmsg);
00653
00654
00655 control_msgs::JointTrajectoryControllerState controllermsg;
00656 controllermsg.header.stamp = time;
00657 controllermsg.joint_names.resize(DOF_);
00658 controllermsg.desired.positions.resize(DOF_);
00659 controllermsg.desired.velocities.resize(DOF_);
00660 controllermsg.actual.positions.resize(DOF_);
00661 controllermsg.actual.velocities.resize(DOF_);
00662 controllermsg.error.positions.resize(DOF_);
00663 controllermsg.error.velocities.resize(DOF_);
00664
00665 controllermsg.joint_names = joint_names_;
00666
00667
00668 if (targetAngles_.size() != 0)
00669 {
00670 controllermsg.desired.positions[0] = targetAngles_[0] * pi_ / 180.0;
00671 controllermsg.desired.positions[1] = targetAngles_[3] * pi_ / 180.0;
00672 controllermsg.desired.positions[2] = targetAngles_[4] * pi_ / 180.0;
00673 controllermsg.desired.positions[3] = targetAngles_[5] * pi_ / 180.0;
00674 controllermsg.desired.positions[4] = targetAngles_[6] * pi_ / 180.0;
00675 controllermsg.desired.positions[5] = targetAngles_[1] * pi_ / 180.0;
00676 controllermsg.desired.positions[6] = targetAngles_[2] * pi_ / 180.0;
00677 }
00678
00679
00680
00681 controllermsg.actual.positions = msg.position;
00682
00683 controllermsg.actual.velocities = msg.velocity;
00684
00685 for (int i = 0; i < DOF_; i++)
00686 {
00687 controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
00688 controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
00689 }
00690
00691 topicPub_ControllerState_.publish(controllermsg);
00692
00693
00694 state_ = sdh_->GetAxisActualState(axes_);
00695 }
00696 else
00697 {
00698 ROS_DEBUG("sdh not initialized");
00699 }
00700
00701 diagnostic_msgs::DiagnosticArray diagnostics;
00702 diagnostics.status.resize(1);
00703
00704 if (isError_)
00705 {
00706 diagnostics.status[0].level = 2;
00707 diagnostics.status[0].name = "schunk_powercube_chain";
00708 diagnostics.status[0].message = "one or more drives are in Error mode";
00709 }
00710 else
00711 {
00712 if (isInitialized_)
00713 {
00714 diagnostics.status[0].level = 0;
00715 diagnostics.status[0].name = nh_.getNamespace();
00716 diagnostics.status[0].message = "sdh initialized and running";
00717 }
00718 else
00719 {
00720 diagnostics.status[0].level = 1;
00721 diagnostics.status[0].name = nh_.getNamespace();
00722 diagnostics.status[0].message = "sdh not initialized";
00723 }
00724 }
00725
00726 topicPub_Diagnostics_.publish(diagnostics);
00727 }
00728 };
00729
00730
00736 int main(int argc, char** argv)
00737 {
00738
00739 ros::init(argc, argv, "schunk_sdh");
00740
00741 SdhNode sdh_node;
00742 if (!sdh_node.init())
00743 return 0;
00744
00745 ROS_INFO("...sdh node running...");
00746
00747 double frequency;
00748 if (sdh_node.nh_private_.hasParam("frequency"))
00749 {
00750 sdh_node.nh_private_.getParam("frequency", frequency);
00751 }
00752 else
00753 {
00754 frequency = 5;
00755 ROS_WARN("Parameter frequency not available, setting to default value: %f Hz", frequency);
00756 }
00757
00758
00759 ros::Rate loop_rate(frequency);
00760 while (sdh_node.nh_.ok())
00761 {
00762
00763 sdh_node.updateSdh();
00764
00765
00766 ros::spinOnce();
00767 loop_rate.sleep();
00768 }
00769
00770 return 0;
00771 }
00772