00001
00060
00061
00062
00063
00064 #include <unistd.h>
00065
00066
00067 #include <ros/ros.h>
00068 #include <urdf/model.h>
00069 #include <actionlib/server/simple_action_server.h>
00070
00071
00072 #include <std_msgs/Float32MultiArray.h>
00073 #include <trajectory_msgs/JointTrajectory.h>
00074 #include <sensor_msgs/JointState.h>
00075 #include <control_msgs/FollowJointTrajectoryAction.h>
00076 #include <control_msgs/JointTrajectoryControllerState.h>
00077 #include <brics_actuator/JointVelocities.h>
00078 #include <brics_actuator/JointValue.h>
00079
00080
00081 #include <cob_srvs/Trigger.h>
00082 #include <cob_srvs/SetOperationMode.h>
00083
00084
00085 #include <diagnostic_msgs/DiagnosticArray.h>
00086
00087
00088 #include <schunk_sdh/sdh.h>
00089
00095 class SdhNode
00096 {
00097 public:
00099 ros::NodeHandle nh_;
00100 private:
00101
00102 ros::Publisher topicPub_JointState_;
00103 ros::Publisher topicPub_ControllerState_;
00104 ros::Publisher topicPub_Diagnostics_;
00105
00106
00107 ros::Subscriber subSetVelocitiesRaw_;
00108 ros::Subscriber subSetVelocities_;
00109
00110
00111 ros::ServiceServer srvServer_Init_;
00112 ros::ServiceServer srvServer_Stop_;
00113 ros::ServiceServer srvServer_Recover_;
00114 ros::ServiceServer srvServer_SetOperationMode_;
00115
00116
00117 actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> as_;
00118 std::string action_name_;
00119
00120
00121
00122
00123
00124 SDH::cSDH *sdh_;
00125 std::vector<SDH::cSDH::eAxisState> state_;
00126
00127 std::string sdhdevicetype_;
00128 std::string sdhdevicestring_;
00129 int sdhdevicenum_;
00130 int baudrate_, id_read_, id_write_;
00131 double timeout_;
00132
00133 bool isInitialized_;
00134 bool isError_;
00135 int DOF_;
00136 double pi_;
00137
00138 trajectory_msgs::JointTrajectory traj_;
00139
00140 std::vector<std::string> joint_names_;
00141 std::vector<int> axes_;
00142 std::vector<double> targetAngles_;
00143 std::vector<double> velocities_;
00144 bool hasNewGoal_;
00145 std::string operationMode_;
00146
00147 public:
00153 SdhNode(std::string name):
00154 as_(nh_, name, boost::bind(&SdhNode::executeCB, this, _1),true),
00155 action_name_(name)
00156 {
00157 pi_ = 3.1415926;
00158
00159 nh_ = ros::NodeHandle ("~");
00160 isError_ = false;
00161
00162 topicPub_Diagnostics_ = nh_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00163
00164 }
00165
00169 ~SdhNode()
00170 {
00171 if(isInitialized_)
00172 sdh_->Close();
00173 delete sdh_;
00174 }
00175
00176
00180 bool init()
00181 {
00182
00183 isInitialized_ = false;
00184 hasNewGoal_ = false;
00185
00186
00187 topicPub_JointState_ = nh_.advertise<sensor_msgs::JointState>("/joint_states", 1);
00188 topicPub_ControllerState_ = nh_.advertise<control_msgs::JointTrajectoryControllerState>("state", 1);
00189
00190
00191 sdh_ = new SDH::cSDH(false, false, 0);
00192
00193
00194 srvServer_Init_ = nh_.advertiseService("init", &SdhNode::srvCallback_Init, this);
00195 srvServer_Stop_ = nh_.advertiseService("stop", &SdhNode::srvCallback_Stop, this);
00196 srvServer_Recover_ = nh_.advertiseService("recover", &SdhNode::srvCallback_Init, this);
00197 srvServer_SetOperationMode_ = nh_.advertiseService("set_operation_mode", &SdhNode::srvCallback_SetOperationMode, this);
00198
00199 subSetVelocitiesRaw_ = nh_.subscribe("set_velocities_raw", 1, &SdhNode::topicCallback_setVelocitiesRaw, this);
00200 subSetVelocities_ = nh_.subscribe("set_velocities", 1, &SdhNode::topicCallback_setVelocities, this);
00201
00202
00203 nh_.param("sdhdevicetype", sdhdevicetype_, std::string("PCAN"));
00204 nh_.param("sdhdevicestring", sdhdevicestring_, std::string("/dev/pcan0"));
00205 nh_.param("sdhdevicenum", sdhdevicenum_, 0);
00206
00207 nh_.param("baudrate", baudrate_, 1000000);
00208 nh_.param("timeout", timeout_, (double)0.04);
00209 nh_.param("id_read", id_read_, 43);
00210 nh_.param("id_write", id_write_, 42);
00211
00212
00213 ROS_INFO("getting joint_names from parameter server");
00214 XmlRpc::XmlRpcValue joint_names_param;
00215 if (nh_.hasParam("joint_names"))
00216 {
00217 nh_.getParam("joint_names", joint_names_param);
00218 }
00219 else
00220 {
00221 ROS_ERROR("Parameter joint_names not set, shutting down node...");
00222 nh_.shutdown();
00223 return false;
00224 }
00225 DOF_ = joint_names_param.size();
00226 joint_names_.resize(DOF_);
00227 for (int i = 0; i<DOF_; i++ )
00228 {
00229 joint_names_[i] = (std::string)joint_names_param[i];
00230 }
00231 std::cout << "joint_names = " << joint_names_param << std::endl;
00232
00233
00234 axes_.resize(DOF_);
00235 velocities_.resize(DOF_);
00236 for(int i=0; i<DOF_; i++)
00237 {
00238 axes_[i] = i;
00239 }
00240 ROS_INFO("DOF = %d",DOF_);
00241
00242 state_.resize(axes_.size());
00243
00244 nh_.param("OperationMode", operationMode_, std::string("position"));
00245 return true;
00246 }
00247
00254 void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
00255 {
00256 ROS_INFO("sdh: executeCB");
00257 if (operationMode_ != "position")
00258 {
00259 ROS_ERROR("%s: Rejected, sdh not in position mode", action_name_.c_str());
00260 as_.setAborted();
00261 return;
00262 }
00263 if (!isInitialized_)
00264 {
00265 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00266 as_.setAborted();
00267 return;
00268 }
00269
00270 if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() != size_t(DOF_))
00271 {
00272 ROS_ERROR("%s: Rejected, malformed FollowJointTrajectoryGoal", action_name_.c_str());
00273 as_.setAborted();
00274 return;
00275 }
00276 while (hasNewGoal_ == true ) usleep(10000);
00277
00278 std::map<std::string,int> dict;
00279 for (int idx=0; idx<goal->trajectory.joint_names.size(); idx++)
00280 {
00281 dict[goal->trajectory.joint_names[idx]] = idx;
00282 }
00283
00284 targetAngles_.resize(DOF_);
00285 targetAngles_[0] = goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]]*180.0/pi_;
00286 targetAngles_[1] = goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]]*180.0/pi_;
00287 targetAngles_[2] = goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]]*180.0/pi_;
00288 targetAngles_[3] = goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]]*180.0/pi_;
00289 targetAngles_[4] = goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]]*180.0/pi_;
00290 targetAngles_[5] = goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]]*180.0/pi_;
00291 targetAngles_[6] = goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]]*180.0/pi_;
00292 ROS_INFO("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]",goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]],goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]],goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]],goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]],goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]],goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]],goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]]);
00293
00294 hasNewGoal_ = true;
00295
00296 usleep(500000);
00297
00298 bool finished = false;
00299 while(finished == false)
00300 {
00301 if (as_.isNewGoalAvailable())
00302 {
00303 ROS_WARN("%s: Aborted", action_name_.c_str());
00304 as_.setAborted();
00305 return;
00306 }
00307 for ( unsigned int i = 0; i < state_.size(); i++ )
00308 {
00309 ROS_DEBUG("state[%d] = %d",i,state_[i]);
00310 if (state_[i] == 0)
00311 {
00312 finished = true;
00313 }
00314 else
00315 {
00316 finished = false;
00317 }
00318 }
00319 usleep(10000);
00320
00321
00322 }
00323
00324
00325 ROS_INFO("%s: Succeeded", action_name_.c_str());
00326
00327
00328
00329 as_.setSucceeded();
00330 }
00331
00332 void topicCallback_setVelocitiesRaw(const std_msgs::Float32MultiArrayPtr& 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 ROS_ERROR("Velocity array dimension mismatch");
00341 return;
00342 }
00343 if (operationMode_ != "velocity")
00344 {
00345 ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
00346 return;
00347 }
00348
00349
00350 while (hasNewGoal_ == true ) usleep(10000);
00351
00352 velocities_[0] = velocities->data[0] * 180.0 / pi_;
00353 velocities_[1] = velocities->data[5] * 180.0 / pi_;
00354 velocities_[2] = velocities->data[6] * 180.0 / pi_;
00355 velocities_[3] = velocities->data[1] * 180.0 / pi_;
00356 velocities_[4] = velocities->data[2] * 180.0 / pi_;
00357 velocities_[5] = velocities->data[3] * 180.0 / pi_;
00358 velocities_[6] = velocities->data[4] * 180.0 / pi_;
00359
00360 hasNewGoal_ = true;
00361 }
00362 bool parseDegFromJointValue(const brics_actuator::JointValue& val, double °_val){
00363 if (val.unit == "rad/s"){
00364 deg_val = val.value * 180.0 / pi_;
00365 return true;
00366 }else if (val.unit == "deg/s"){
00367 deg_val = val.value;
00368 return true;
00369 }else {
00370 ROS_ERROR_STREAM("Rejected message, unit '" << val.unit << "' not supported");
00371 return false;
00372 }
00373 }
00374 void topicCallback_setVelocities(const brics_actuator::JointVelocities::ConstPtr& msg)
00375 {
00376 if (!isInitialized_)
00377 {
00378 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00379 return;
00380 }
00381 if(msg->velocities.size() != velocities_.size()){
00382 ROS_ERROR("Velocity array dimension mismatch");
00383 return;
00384 }
00385 if (operationMode_ != "velocity")
00386 {
00387 ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
00388 return;
00389 }
00390
00391
00392 while (hasNewGoal_ == true ) usleep(10000);
00393 bool valid = true;
00394
00395 valid = valid && parseDegFromJointValue(msg->velocities[0], velocities_[0]);
00396 valid = valid && parseDegFromJointValue(msg->velocities[5], velocities_[1]);
00397 valid = valid && parseDegFromJointValue(msg->velocities[6], velocities_[2]);
00398 valid = valid && parseDegFromJointValue(msg->velocities[1], velocities_[3]);
00399 valid = valid && parseDegFromJointValue(msg->velocities[2], velocities_[4]);
00400 valid = valid && parseDegFromJointValue(msg->velocities[3], velocities_[5]);
00401 valid = valid && parseDegFromJointValue(msg->velocities[4], velocities_[6]);
00402
00403 if (valid) hasNewGoal_ = true;
00404 }
00412 bool srvCallback_Init(cob_srvs::Trigger::Request &req,
00413 cob_srvs::Trigger::Response &res )
00414 {
00415
00416 if (isInitialized_ == false)
00417 {
00418
00419
00420 try
00421 {
00422 if(sdhdevicetype_.compare("RS232")==0)
00423 {
00424 sdh_->OpenRS232( sdhdevicenum_, 115200, 1, sdhdevicestring_.c_str());
00425 ROS_INFO("Initialized RS232 for SDH");
00426 isInitialized_ = true;
00427 }
00428 if(sdhdevicetype_.compare("PCAN")==0)
00429 {
00430 ROS_INFO("Starting initializing PEAKCAN");
00431 sdh_->OpenCAN_PEAK(baudrate_, timeout_, id_read_, id_write_, sdhdevicestring_.c_str());
00432 ROS_INFO("Initialized PEAK CAN for SDH");
00433 isInitialized_ = true;
00434 }
00435 if(sdhdevicetype_.compare("ESD")==0)
00436 {
00437 ROS_INFO("Starting initializing ESD");
00438 if(strcmp(sdhdevicestring_.c_str(), "/dev/can0") == 0)
00439 {
00440 ROS_INFO("Initializing ESD on device %s",sdhdevicestring_.c_str());
00441 sdh_->OpenCAN_ESD(0, baudrate_, timeout_, id_read_, id_write_ );
00442 }
00443 else if(strcmp(sdhdevicestring_.c_str(), "/dev/can1") == 0)
00444 {
00445 ROS_INFO("Initializin ESD on device %s",sdhdevicestring_.c_str());
00446 sdh_->OpenCAN_ESD(1, baudrate_, timeout_, id_read_, id_write_ );
00447 }
00448 else
00449 {
00450 ROS_ERROR("Currently only support for /dev/can0 and /dev/can1");
00451 res.success.data = false;
00452 res.error_message.data = "Currently only support for /dev/can0 and /dev/can1";
00453 return true;
00454 }
00455 ROS_INFO("Initialized ESDCAN for SDH");
00456 isInitialized_ = true;
00457 }
00458 }
00459 catch (SDH::cSDHLibraryException* e)
00460 {
00461 ROS_ERROR("An exception was caught: %s", e->what());
00462 res.success.data = false;
00463 res.error_message.data = e->what();
00464 delete e;
00465 return true;
00466 }
00467 }
00468 else
00469 {
00470 ROS_WARN("...sdh already initialized...");
00471 res.success.data = true;
00472 res.error_message.data = "sdh already initialized";
00473 }
00474
00475 res.success.data = true;
00476 return true;
00477 }
00478
00486 bool srvCallback_Stop(cob_srvs::Trigger::Request &req,
00487 cob_srvs::Trigger::Response &res )
00488 {
00489 ROS_INFO("Stopping sdh");
00490
00491
00492 try
00493 {
00494 sdh_->Stop();
00495 }
00496 catch (SDH::cSDHLibraryException* e)
00497 {
00498 ROS_ERROR("An exception was caught: %s", e->what());
00499 delete e;
00500 }
00501
00502 ROS_INFO("Stopping sdh succesfull");
00503 res.success.data = true;
00504 return true;
00505 }
00506
00514 bool srvCallback_Recover(cob_srvs::Trigger::Request &req,
00515 cob_srvs::Trigger::Response &res )
00516 {
00517 ROS_WARN("Service recover not implemented yet");
00518 res.success.data = true;
00519 res.error_message.data = "Service recover not implemented yet";
00520 return true;
00521 }
00522
00530 bool srvCallback_SetOperationMode(cob_srvs::SetOperationMode::Request &req,
00531 cob_srvs::SetOperationMode::Response &res )
00532 {
00533 hasNewGoal_ = false;
00534 sdh_->Stop();
00535 ROS_INFO("Set operation mode to [%s]", req.operation_mode.data.c_str());
00536 operationMode_ = req.operation_mode.data;
00537 res.success.data = true;
00538 if( operationMode_ == "position"){
00539 sdh_->SetController(SDH::cSDH::eCT_POSE);
00540 }else if( operationMode_ == "velocity"){
00541 try{
00542 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
00543 sdh_->SetAxisEnable(sdh_->All, 1.0);
00544 }
00545 catch (SDH::cSDHLibraryException* e)
00546 {
00547 ROS_ERROR("An exception was caught: %s", e->what());
00548 delete e;
00549 }
00550 }else{
00551 ROS_ERROR_STREAM("Operation mode '" << req.operation_mode.data << "' not supported");
00552 }
00553 return true;
00554 }
00555
00561 void updateSdh()
00562 {
00563 ROS_DEBUG("updateJointState");
00564 if (isInitialized_ == true)
00565 {
00566 if (hasNewGoal_ == true)
00567 {
00568
00569 try
00570 {
00571 sdh_->Stop();
00572 }
00573 catch (SDH::cSDHLibraryException* e)
00574 {
00575 ROS_ERROR("An exception was caught: %s", e->what());
00576 delete e;
00577 }
00578
00579 if (operationMode_ == "position")
00580 {
00581 ROS_DEBUG("moving sdh in position mode");
00582
00583 try
00584 {
00585 sdh_->SetAxisTargetAngle( axes_, targetAngles_ );
00586 sdh_->MoveHand(false);
00587 }
00588 catch (SDH::cSDHLibraryException* e)
00589 {
00590 ROS_ERROR("An exception was caught: %s", e->what());
00591 delete e;
00592 }
00593 }
00594 else if (operationMode_ == "velocity")
00595 {
00596 ROS_DEBUG("moving sdh in velocity mode");
00597 try
00598 {
00599 sdh_->SetAxisTargetVelocity(axes_,velocities_);
00600
00601 }
00602 catch (SDH::cSDHLibraryException* e)
00603 {
00604 ROS_ERROR("An exception was caught: %s", e->what());
00605 delete e;
00606 }
00607 }
00608 else if (operationMode_ == "effort")
00609 {
00610 ROS_DEBUG("moving sdh in effort mode");
00611
00612 ROS_WARN("Moving in effort mode currently disabled");
00613 }
00614 else
00615 {
00616 ROS_ERROR("sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]", operationMode_.c_str());
00617 }
00618
00619 hasNewGoal_ = false;
00620 }
00621
00622
00623 std::vector<double> actualAngles;
00624 try
00625 {
00626 actualAngles = sdh_->GetAxisActualAngle( axes_ );
00627 }
00628 catch (SDH::cSDHLibraryException* e)
00629 {
00630 ROS_ERROR("An exception was caught: %s", e->what());
00631 delete e;
00632 }
00633 std::vector<double> actualVelocities;
00634 try
00635 {
00636 actualVelocities = sdh_->GetAxisActualVelocity( axes_ );
00637 }
00638 catch (SDH::cSDHLibraryException* e)
00639 {
00640 ROS_ERROR("An exception was caught: %s", e->what());
00641 delete e;
00642 }
00643
00644 ROS_DEBUG("received %d angles from sdh",(int)actualAngles.size());
00645
00646 ros::Time time = ros::Time::now();
00647
00648
00649 sensor_msgs::JointState msg;
00650 msg.header.stamp = time;
00651 msg.name.resize(DOF_);
00652 msg.position.resize(DOF_);
00653 msg.velocity.resize(DOF_);
00654 msg.effort.resize(DOF_);
00655
00656 msg.name = joint_names_;
00657
00658
00659 msg.position[0] = actualAngles[0]*pi_/180.0;
00660 msg.position[1] = actualAngles[3]*pi_/180.0;
00661 msg.position[2] = actualAngles[4]*pi_/180.0;
00662 msg.position[3] = actualAngles[5]*pi_/180.0;
00663 msg.position[4] = actualAngles[6]*pi_/180.0;
00664 msg.position[5] = actualAngles[1]*pi_/180.0;
00665 msg.position[6] = actualAngles[2]*pi_/180.0;
00666
00667 msg.velocity[0] = actualVelocities[0]*pi_/180.0;
00668 msg.velocity[1] = actualVelocities[3]*pi_/180.0;
00669 msg.velocity[2] = actualVelocities[4]*pi_/180.0;
00670 msg.velocity[3] = actualVelocities[5]*pi_/180.0;
00671 msg.velocity[4] = actualVelocities[6]*pi_/180.0;
00672 msg.velocity[5] = actualVelocities[1]*pi_/180.0;
00673 msg.velocity[6] = actualVelocities[2]*pi_/180.0;
00674
00675 topicPub_JointState_.publish(msg);
00676
00677
00678
00679 sensor_msgs::JointState mimicjointmsg;
00680 mimicjointmsg.header.stamp = time;
00681 mimicjointmsg.name.resize(1);
00682 mimicjointmsg.position.resize(1);
00683 mimicjointmsg.velocity.resize(1);
00684 mimicjointmsg.name[0] = "sdh_finger_21_joint";
00685 mimicjointmsg.position[0] = msg.position[0];
00686 mimicjointmsg.velocity[0] = msg.velocity[0];
00687 topicPub_JointState_.publish(mimicjointmsg);
00688
00689
00690
00691 control_msgs::JointTrajectoryControllerState controllermsg;
00692 controllermsg.header.stamp = time;
00693 controllermsg.joint_names.resize(DOF_);
00694 controllermsg.desired.positions.resize(DOF_);
00695 controllermsg.desired.velocities.resize(DOF_);
00696 controllermsg.actual.positions.resize(DOF_);
00697 controllermsg.actual.velocities.resize(DOF_);
00698 controllermsg.error.positions.resize(DOF_);
00699 controllermsg.error.velocities.resize(DOF_);
00700
00701 controllermsg.joint_names = joint_names_;
00702
00703
00704 if (targetAngles_.size() != 0)
00705 {
00706 controllermsg.desired.positions[0] = targetAngles_[0]*pi_/180.0;
00707 controllermsg.desired.positions[1] = targetAngles_[3]*pi_/180.0;
00708 controllermsg.desired.positions[2] = targetAngles_[4]*pi_/180.0;
00709 controllermsg.desired.positions[3] = targetAngles_[5]*pi_/180.0;
00710 controllermsg.desired.positions[4] = targetAngles_[6]*pi_/180.0;
00711 controllermsg.desired.positions[5] = targetAngles_[1]*pi_/180.0;
00712 controllermsg.desired.positions[6] = targetAngles_[2]*pi_/180.0;
00713 }
00714
00715
00716
00717 controllermsg.actual.positions = msg.position;
00718
00719 controllermsg.actual.velocities = msg.velocity;
00720
00721 for (int i = 0; i<DOF_; i++ )
00722 {
00723 controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
00724 controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
00725 }
00726
00727 topicPub_ControllerState_.publish(controllermsg);
00728
00729
00730 state_ = sdh_->GetAxisActualState(axes_);
00731 }
00732 else
00733 {
00734 ROS_DEBUG("sdh not initialized");
00735 }
00736
00737 diagnostic_msgs::DiagnosticArray diagnostics;
00738 diagnostics.status.resize(1);
00739
00740 if(isError_)
00741 {
00742 diagnostics.status[0].level = 2;
00743 diagnostics.status[0].name = "schunk_powercube_chain";
00744 diagnostics.status[0].message = "one or more drives are in Error mode";
00745 }
00746 else
00747 {
00748 if (isInitialized_)
00749 {
00750 diagnostics.status[0].level = 0;
00751 diagnostics.status[0].name = nh_.getNamespace();
00752 diagnostics.status[0].message = "sdh initialized and running";
00753 }
00754 else
00755 {
00756 diagnostics.status[0].level = 1;
00757 diagnostics.status[0].name = nh_.getNamespace();
00758 diagnostics.status[0].message = "sdh not initialized";
00759 }
00760 }
00761
00762 topicPub_Diagnostics_.publish(diagnostics);
00763
00764 }
00765 };
00766
00772 int main(int argc, char** argv)
00773 {
00774
00775 ros::init(argc, argv, "schunk_sdh");
00776
00777
00778 SdhNode sdh_node(ros::this_node::getName() + "/follow_joint_trajectory");
00779 if (!sdh_node.init()) return 0;
00780
00781 ROS_INFO("...sdh node running...");
00782
00783 double frequency;
00784 if (sdh_node.nh_.hasParam("frequency"))
00785 {
00786 sdh_node.nh_.getParam("frequency", frequency);
00787 }
00788 else
00789 {
00790 frequency = 5;
00791 ROS_WARN("Parameter frequency not available, setting to default value: %f Hz", frequency);
00792 }
00793
00794
00795 ros::Rate loop_rate(frequency);
00796 while(sdh_node.nh_.ok())
00797 {
00798
00799 sdh_node.updateSdh();
00800
00801
00802 ros::spinOnce();
00803 loop_rate.sleep();
00804 }
00805
00806 return 0;
00807 }
00808