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 <schunk_sdh/TactileSensor.h>
00078 #include <schunk_sdh/TactileMatrix.h>
00079 #include <brics_actuator/JointVelocities.h>
00080 #include <brics_actuator/JointValue.h>
00081
00082
00083 #include <cob_srvs/Trigger.h>
00084 #include <cob_srvs/SetOperationMode.h>
00085
00086
00087 #include <diagnostic_msgs/DiagnosticArray.h>
00088
00089
00090 #include <schunk_sdh/sdh.h>
00091 #include <schunk_sdh/dsa.h>
00092
00098 class SdhNode
00099 {
00100 public:
00102 ros::NodeHandle nh_;
00103 private:
00104
00105 ros::Publisher topicPub_JointState_;
00106 ros::Publisher topicPub_ControllerState_;
00107 ros::Publisher topicPub_TactileSensor_;
00108 ros::Publisher topicPub_Diagnostics_;
00109
00110
00111 ros::Subscriber subSetVelocitiesRaw_;
00112 ros::Subscriber subSetVelocities_;
00113
00114
00115 ros::ServiceServer srvServer_Init_;
00116 ros::ServiceServer srvServer_Stop_;
00117 ros::ServiceServer srvServer_Recover_;
00118 ros::ServiceServer srvServer_SetOperationMode_;
00119
00120
00121 actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> as_;
00122 std::string action_name_;
00123
00124
00125
00126
00127
00128 SDH::cSDH *sdh_;
00129 SDH::cDSA *dsa_;
00130 std::vector<SDH::cSDH::eAxisState> state_;
00131
00132 std::string sdhdevicetype_;
00133 std::string sdhdevicestring_;
00134 int sdhdevicenum_;
00135 std::string dsadevicestring_;
00136 int dsadevicenum_;
00137 int baudrate_, id_read_, id_write_;
00138 double timeout_;
00139
00140 bool isInitialized_;
00141 bool isDSAInitialized_;
00142 bool isError_;
00143 int DOF_;
00144 double pi_;
00145
00146 trajectory_msgs::JointTrajectory traj_;
00147
00148 std::vector<std::string> joint_names_;
00149 std::vector<int> axes_;
00150 std::vector<double> targetAngles_;
00151 std::vector<double> velocities_;
00152 bool hasNewGoal_;
00153 std::string operationMode_;
00154
00155 public:
00161 SdhNode(std::string name):
00162 as_(nh_, name, boost::bind(&SdhNode::executeCB, this, _1),true),
00163 action_name_(name)
00164 {
00165 pi_ = 3.1415926;
00166
00167 nh_ = ros::NodeHandle ("~");
00168 isError_ = false;
00169
00170 topicPub_Diagnostics_ = nh_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00171
00172 }
00173
00177 ~SdhNode()
00178 {
00179 if(isDSAInitialized_)
00180 dsa_->Close();
00181 if(isInitialized_)
00182 sdh_->Close();
00183 delete sdh_;
00184 }
00185
00186
00190 bool init()
00191 {
00192
00193 isInitialized_ = false;
00194 isDSAInitialized_ = false;
00195 hasNewGoal_ = false;
00196
00197
00198 topicPub_JointState_ = nh_.advertise<sensor_msgs::JointState>("/joint_states", 1);
00199 topicPub_ControllerState_ = nh_.advertise<control_msgs::JointTrajectoryControllerState>("state", 1);
00200 topicPub_TactileSensor_ = nh_.advertise<schunk_sdh::TactileSensor>("tactile_data", 1);
00201
00202
00203 sdh_ = new SDH::cSDH(false, false, 0);
00204
00205
00206 srvServer_Init_ = nh_.advertiseService("init", &SdhNode::srvCallback_Init, this);
00207 srvServer_Stop_ = nh_.advertiseService("stop", &SdhNode::srvCallback_Stop, this);
00208 srvServer_Recover_ = nh_.advertiseService("recover", &SdhNode::srvCallback_Init, this);
00209 srvServer_SetOperationMode_ = nh_.advertiseService("set_operation_mode", &SdhNode::srvCallback_SetOperationMode, this);
00210
00211 subSetVelocitiesRaw_ = nh_.subscribe("set_velocities_raw", 1, &SdhNode::topicCallback_setVelocitiesRaw, this);
00212 subSetVelocities_ = nh_.subscribe("set_velocities", 1, &SdhNode::topicCallback_setVelocities, this);
00213
00214
00215 nh_.param("sdhdevicetype", sdhdevicetype_, std::string("PCAN"));
00216 nh_.param("sdhdevicestring", sdhdevicestring_, std::string("/dev/pcan0"));
00217 nh_.param("sdhdevicenum", sdhdevicenum_, 0);
00218
00219 nh_.param("dsadevicestring", dsadevicestring_, std::string(""));
00220 nh_.param("dsadevicenum", dsadevicenum_, 0);
00221
00222 nh_.param("baudrate", baudrate_, 1000000);
00223 nh_.param("timeout", timeout_, (double)0.04);
00224 nh_.param("id_read", id_read_, 43);
00225 nh_.param("id_write", id_write_, 42);
00226
00227
00228 ROS_INFO("getting joint_names from parameter server");
00229 XmlRpc::XmlRpcValue joint_names_param;
00230 if (nh_.hasParam("joint_names"))
00231 {
00232 nh_.getParam("joint_names", joint_names_param);
00233 }
00234 else
00235 {
00236 ROS_ERROR("Parameter joint_names not set, shutting down node...");
00237 nh_.shutdown();
00238 return false;
00239 }
00240 DOF_ = joint_names_param.size();
00241 joint_names_.resize(DOF_);
00242 for (int i = 0; i<DOF_; i++ )
00243 {
00244 joint_names_[i] = (std::string)joint_names_param[i];
00245 }
00246 std::cout << "joint_names = " << joint_names_param << std::endl;
00247
00248
00249 axes_.resize(DOF_);
00250 velocities_.resize(DOF_);
00251 for(int i=0; i<DOF_; i++)
00252 {
00253 axes_[i] = i;
00254 }
00255 ROS_INFO("DOF = %d",DOF_);
00256
00257 state_.resize(axes_.size());
00258
00259 nh_.param("OperationMode", operationMode_, std::string("position"));
00260 return true;
00261 }
00262
00269 void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
00270 {
00271 ROS_INFO("sdh: executeCB");
00272 if (operationMode_ != "position")
00273 {
00274 ROS_ERROR("%s: Rejected, sdh not in position mode", action_name_.c_str());
00275 as_.setAborted();
00276 return;
00277 }
00278 if (!isInitialized_)
00279 {
00280 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00281 as_.setAborted();
00282 return;
00283 }
00284
00285 if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() != size_t(DOF_))
00286 {
00287 ROS_ERROR("%s: Rejected, malformed FollowJointTrajectoryGoal", action_name_.c_str());
00288 as_.setAborted();
00289 return;
00290 }
00291 while (hasNewGoal_ == true ) usleep(10000);
00292
00293 std::map<std::string,int> dict;
00294 for (int idx=0; idx<goal->trajectory.joint_names.size(); idx++)
00295 {
00296 dict[goal->trajectory.joint_names[idx]] = idx;
00297 }
00298
00299 targetAngles_.resize(DOF_);
00300 targetAngles_[0] = goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]]*180.0/pi_;
00301 targetAngles_[1] = goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]]*180.0/pi_;
00302 targetAngles_[2] = goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]]*180.0/pi_;
00303 targetAngles_[3] = goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]]*180.0/pi_;
00304 targetAngles_[4] = goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]]*180.0/pi_;
00305 targetAngles_[5] = goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]]*180.0/pi_;
00306 targetAngles_[6] = goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]]*180.0/pi_;
00307 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"]]);
00308
00309 hasNewGoal_ = true;
00310
00311 usleep(500000);
00312
00313 bool finished = false;
00314 while(finished == false)
00315 {
00316 if (as_.isNewGoalAvailable())
00317 {
00318 ROS_WARN("%s: Aborted", action_name_.c_str());
00319 as_.setAborted();
00320 return;
00321 }
00322 for ( unsigned int i = 0; i < state_.size(); i++ )
00323 {
00324 ROS_DEBUG("state[%d] = %d",i,state_[i]);
00325 if (state_[i] == 0)
00326 {
00327 finished = true;
00328 }
00329 else
00330 {
00331 finished = false;
00332 }
00333 }
00334 usleep(10000);
00335
00336
00337 }
00338
00339
00340 ROS_INFO("%s: Succeeded", action_name_.c_str());
00341
00342
00343
00344 as_.setSucceeded();
00345 }
00346
00347 void topicCallback_setVelocitiesRaw(const std_msgs::Float32MultiArrayPtr& velocities)
00348 {
00349 if (!isInitialized_)
00350 {
00351 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00352 return;
00353 }
00354 if(velocities->data.size() != velocities_.size()){
00355 ROS_ERROR("Velocity array dimension mismatch");
00356 return;
00357 }
00358 if (operationMode_ != "velocity")
00359 {
00360 ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
00361 return;
00362 }
00363
00364
00365 while (hasNewGoal_ == true ) usleep(10000);
00366
00367 velocities_[0] = velocities->data[0] * 180.0 / pi_;
00368 velocities_[1] = velocities->data[5] * 180.0 / pi_;
00369 velocities_[2] = velocities->data[6] * 180.0 / pi_;
00370 velocities_[3] = velocities->data[1] * 180.0 / pi_;
00371 velocities_[4] = velocities->data[2] * 180.0 / pi_;
00372 velocities_[5] = velocities->data[3] * 180.0 / pi_;
00373 velocities_[6] = velocities->data[4] * 180.0 / pi_;
00374
00375 hasNewGoal_ = true;
00376 }
00377 bool parseDegFromJointValue(const brics_actuator::JointValue& val, double °_val){
00378 if (val.unit == "rad/s"){
00379 deg_val = val.value * 180.0 / pi_;
00380 return true;
00381 }else if (val.unit == "deg/s"){
00382 deg_val = val.value;
00383 return true;
00384 }else {
00385 ROS_ERROR_STREAM("Rejected message, unit '" << val.unit << "' not supported");
00386 return false;
00387 }
00388 }
00389 void topicCallback_setVelocities(const brics_actuator::JointVelocities::ConstPtr& msg)
00390 {
00391 if (!isInitialized_)
00392 {
00393 ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
00394 return;
00395 }
00396 if(msg->velocities.size() != velocities_.size()){
00397 ROS_ERROR("Velocity array dimension mismatch");
00398 return;
00399 }
00400 if (operationMode_ != "velocity")
00401 {
00402 ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
00403 return;
00404 }
00405
00406
00407 while (hasNewGoal_ == true ) usleep(10000);
00408 bool valid = true;
00409
00410 valid = valid && parseDegFromJointValue(msg->velocities[0], velocities_[0]);
00411 valid = valid && parseDegFromJointValue(msg->velocities[5], velocities_[1]);
00412 valid = valid && parseDegFromJointValue(msg->velocities[6], velocities_[2]);
00413 valid = valid && parseDegFromJointValue(msg->velocities[1], velocities_[3]);
00414 valid = valid && parseDegFromJointValue(msg->velocities[2], velocities_[4]);
00415 valid = valid && parseDegFromJointValue(msg->velocities[3], velocities_[5]);
00416 valid = valid && parseDegFromJointValue(msg->velocities[4], velocities_[6]);
00417
00418 if (valid) hasNewGoal_ = true;
00419 }
00427 bool srvCallback_Init(cob_srvs::Trigger::Request &req,
00428 cob_srvs::Trigger::Response &res )
00429 {
00430
00431 if (isInitialized_ == false)
00432 {
00433
00434
00435 try
00436 {
00437 if(sdhdevicetype_.compare("RS232")==0)
00438 {
00439 sdh_->OpenRS232( sdhdevicenum_, 115200, 1, sdhdevicestring_.c_str());
00440 ROS_INFO("Initialized RS232 for SDH");
00441 isInitialized_ = true;
00442 }
00443 if(sdhdevicetype_.compare("PCAN")==0)
00444 {
00445 ROS_INFO("Starting initializing PEAKCAN");
00446 sdh_->OpenCAN_PEAK(baudrate_, timeout_, id_read_, id_write_, sdhdevicestring_.c_str());
00447 ROS_INFO("Initialized PEAK CAN for SDH");
00448 isInitialized_ = true;
00449 }
00450 if(sdhdevicetype_.compare("ESD")==0)
00451 {
00452 ROS_INFO("Starting initializing ESD");
00453 if(strcmp(sdhdevicestring_.c_str(), "/dev/can0") == 0)
00454 {
00455 ROS_INFO("Initializing ESD on device %s",sdhdevicestring_.c_str());
00456 sdh_->OpenCAN_ESD(0, baudrate_, timeout_, id_read_, id_write_ );
00457 }
00458 else if(strcmp(sdhdevicestring_.c_str(), "/dev/can1") == 0)
00459 {
00460 ROS_INFO("Initializin ESD on device %s",sdhdevicestring_.c_str());
00461 sdh_->OpenCAN_ESD(1, baudrate_, timeout_, id_read_, id_write_ );
00462 }
00463 else
00464 {
00465 ROS_ERROR("Currently only support for /dev/can0 and /dev/can1");
00466 res.success.data = false;
00467 res.error_message.data = "Currently only support for /dev/can0 and /dev/can1";
00468 return true;
00469 }
00470 ROS_INFO("Initialized ESDCAN for SDH");
00471 isInitialized_ = true;
00472 }
00473 }
00474 catch (SDH::cSDHLibraryException* e)
00475 {
00476 ROS_ERROR("An exception was caught: %s", e->what());
00477 res.success.data = false;
00478 res.error_message.data = e->what();
00479 delete e;
00480 return true;
00481 }
00482
00483
00484 if(!dsadevicestring_.empty()) {
00485 try
00486 {
00487 dsa_ = new SDH::cDSA(0, dsadevicenum_, dsadevicestring_.c_str());
00488
00489 dsa_->SetFramerate( 1, true );
00490 ROS_INFO("Initialized RS232 for DSA Tactile Sensors on device %s",dsadevicestring_.c_str());
00491
00492
00493
00494 isDSAInitialized_ = true;
00495 }
00496 catch (SDH::cSDHLibraryException* e)
00497 {
00498 isDSAInitialized_ = false;
00499 ROS_ERROR("An exception was caught: %s", e->what());
00500 res.success.data = false;
00501 res.error_message.data = e->what();
00502 delete e;
00503 return true;
00504 }
00505 }
00506 }
00507 else
00508 {
00509 ROS_WARN("...sdh already initialized...");
00510 res.success.data = true;
00511 res.error_message.data = "sdh already initialized";
00512 }
00513
00514 res.success.data = true;
00515 return true;
00516 }
00517
00525 bool srvCallback_Stop(cob_srvs::Trigger::Request &req,
00526 cob_srvs::Trigger::Response &res )
00527 {
00528 ROS_INFO("Stopping sdh");
00529
00530
00531 try
00532 {
00533 sdh_->Stop();
00534 }
00535 catch (SDH::cSDHLibraryException* e)
00536 {
00537 ROS_ERROR("An exception was caught: %s", e->what());
00538 delete e;
00539 }
00540
00541 ROS_INFO("Stopping sdh succesfull");
00542 res.success.data = true;
00543 return true;
00544 }
00545
00553 bool srvCallback_Recover(cob_srvs::Trigger::Request &req,
00554 cob_srvs::Trigger::Response &res )
00555 {
00556 ROS_WARN("Service recover not implemented yet");
00557 res.success.data = true;
00558 res.error_message.data = "Service recover not implemented yet";
00559 return true;
00560 }
00561
00569 bool srvCallback_SetOperationMode(cob_srvs::SetOperationMode::Request &req,
00570 cob_srvs::SetOperationMode::Response &res )
00571 {
00572 hasNewGoal_ = false;
00573 sdh_->Stop();
00574 ROS_INFO("Set operation mode to [%s]", req.operation_mode.data.c_str());
00575 operationMode_ = req.operation_mode.data;
00576 res.success.data = true;
00577 if( operationMode_ == "position"){
00578 sdh_->SetController(SDH::cSDH::eCT_POSE);
00579 }else if( operationMode_ == "velocity"){
00580 try{
00581 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
00582 sdh_->SetAxisEnable(sdh_->All, 1.0);
00583 }
00584 catch (SDH::cSDHLibraryException* e)
00585 {
00586 ROS_ERROR("An exception was caught: %s", e->what());
00587 delete e;
00588 }
00589 }else{
00590 ROS_ERROR_STREAM("Operation mode '" << req.operation_mode.data << "' not supported");
00591 }
00592 return true;
00593 }
00594
00600 void updateSdh()
00601 {
00602 ROS_DEBUG("updateJointState");
00603 if (isInitialized_ == true)
00604 {
00605 if (hasNewGoal_ == true)
00606 {
00607
00608 try
00609 {
00610 sdh_->Stop();
00611 }
00612 catch (SDH::cSDHLibraryException* e)
00613 {
00614 ROS_ERROR("An exception was caught: %s", e->what());
00615 delete e;
00616 }
00617
00618 if (operationMode_ == "position")
00619 {
00620 ROS_DEBUG("moving sdh in position mode");
00621
00622 try
00623 {
00624 sdh_->SetAxisTargetAngle( axes_, targetAngles_ );
00625 sdh_->MoveHand(false);
00626 }
00627 catch (SDH::cSDHLibraryException* e)
00628 {
00629 ROS_ERROR("An exception was caught: %s", e->what());
00630 delete e;
00631 }
00632 }
00633 else if (operationMode_ == "velocity")
00634 {
00635 ROS_DEBUG("moving sdh in velocity mode");
00636 try
00637 {
00638 sdh_->SetAxisTargetVelocity(axes_,velocities_);
00639
00640 }
00641 catch (SDH::cSDHLibraryException* e)
00642 {
00643 ROS_ERROR("An exception was caught: %s", e->what());
00644 delete e;
00645 }
00646 }
00647 else if (operationMode_ == "effort")
00648 {
00649 ROS_DEBUG("moving sdh in effort mode");
00650
00651 ROS_WARN("Moving in effort mode currently disabled");
00652 }
00653 else
00654 {
00655 ROS_ERROR("sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]", operationMode_.c_str());
00656 }
00657
00658 hasNewGoal_ = false;
00659 }
00660
00661
00662 std::vector<double> actualAngles;
00663 try
00664 {
00665 actualAngles = sdh_->GetAxisActualAngle( axes_ );
00666 }
00667 catch (SDH::cSDHLibraryException* e)
00668 {
00669 ROS_ERROR("An exception was caught: %s", e->what());
00670 delete e;
00671 }
00672 std::vector<double> actualVelocities;
00673 try
00674 {
00675 actualVelocities = sdh_->GetAxisActualVelocity( axes_ );
00676 }
00677 catch (SDH::cSDHLibraryException* e)
00678 {
00679 ROS_ERROR("An exception was caught: %s", e->what());
00680 delete e;
00681 }
00682
00683 ROS_DEBUG("received %d angles from sdh",(int)actualAngles.size());
00684
00685 ros::Time time = ros::Time::now();
00686
00687
00688 sensor_msgs::JointState msg;
00689 msg.header.stamp = time;
00690 msg.name.resize(DOF_);
00691 msg.position.resize(DOF_);
00692 msg.velocity.resize(DOF_);
00693 msg.effort.resize(DOF_);
00694
00695 msg.name = joint_names_;
00696
00697
00698 msg.position[0] = actualAngles[0]*pi_/180.0;
00699 msg.position[1] = actualAngles[3]*pi_/180.0;
00700 msg.position[2] = actualAngles[4]*pi_/180.0;
00701 msg.position[3] = actualAngles[5]*pi_/180.0;
00702 msg.position[4] = actualAngles[6]*pi_/180.0;
00703 msg.position[5] = actualAngles[1]*pi_/180.0;
00704 msg.position[6] = actualAngles[2]*pi_/180.0;
00705
00706 msg.velocity[0] = actualVelocities[0]*pi_/180.0;
00707 msg.velocity[1] = actualVelocities[3]*pi_/180.0;
00708 msg.velocity[2] = actualVelocities[4]*pi_/180.0;
00709 msg.velocity[3] = actualVelocities[5]*pi_/180.0;
00710 msg.velocity[4] = actualVelocities[6]*pi_/180.0;
00711 msg.velocity[5] = actualVelocities[1]*pi_/180.0;
00712 msg.velocity[6] = actualVelocities[2]*pi_/180.0;
00713
00714 topicPub_JointState_.publish(msg);
00715
00716
00717
00718 sensor_msgs::JointState mimicjointmsg;
00719 mimicjointmsg.header.stamp = time;
00720 mimicjointmsg.name.resize(1);
00721 mimicjointmsg.position.resize(1);
00722 mimicjointmsg.velocity.resize(1);
00723 mimicjointmsg.name[0] = "sdh_finger_21_joint";
00724 mimicjointmsg.position[0] = msg.position[0];
00725 mimicjointmsg.velocity[0] = msg.velocity[0];
00726 topicPub_JointState_.publish(mimicjointmsg);
00727
00728
00729
00730 control_msgs::JointTrajectoryControllerState controllermsg;
00731 controllermsg.header.stamp = time;
00732 controllermsg.joint_names.resize(DOF_);
00733 controllermsg.desired.positions.resize(DOF_);
00734 controllermsg.desired.velocities.resize(DOF_);
00735 controllermsg.actual.positions.resize(DOF_);
00736 controllermsg.actual.velocities.resize(DOF_);
00737 controllermsg.error.positions.resize(DOF_);
00738 controllermsg.error.velocities.resize(DOF_);
00739
00740 controllermsg.joint_names = joint_names_;
00741
00742
00743 if (targetAngles_.size() != 0)
00744 {
00745 controllermsg.desired.positions[0] = targetAngles_[0]*pi_/180.0;
00746 controllermsg.desired.positions[1] = targetAngles_[3]*pi_/180.0;
00747 controllermsg.desired.positions[2] = targetAngles_[4]*pi_/180.0;
00748 controllermsg.desired.positions[3] = targetAngles_[5]*pi_/180.0;
00749 controllermsg.desired.positions[4] = targetAngles_[6]*pi_/180.0;
00750 controllermsg.desired.positions[5] = targetAngles_[1]*pi_/180.0;
00751 controllermsg.desired.positions[6] = targetAngles_[2]*pi_/180.0;
00752 }
00753
00754
00755
00756 controllermsg.actual.positions = msg.position;
00757
00758 controllermsg.actual.velocities = msg.velocity;
00759
00760 for (int i = 0; i<DOF_; i++ )
00761 {
00762 controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
00763 controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
00764 }
00765
00766 topicPub_ControllerState_.publish(controllermsg);
00767
00768
00769 state_ = sdh_->GetAxisActualState(axes_);
00770 }
00771 else
00772 {
00773 ROS_DEBUG("sdh not initialized");
00774 }
00775
00776 diagnostic_msgs::DiagnosticArray diagnostics;
00777 diagnostics.status.resize(1);
00778
00779 if(isError_)
00780 {
00781 diagnostics.status[0].level = 2;
00782 diagnostics.status[0].name = "schunk_powercube_chain";
00783 diagnostics.status[0].message = "one or more drives are in Error mode";
00784 }
00785 else
00786 {
00787 if (isInitialized_)
00788 {
00789 diagnostics.status[0].level = 0;
00790 diagnostics.status[0].name = nh_.getNamespace();
00791 if(isDSAInitialized_)
00792 diagnostics.status[0].message = "sdh with tactile sensing initialized and running";
00793 else
00794 diagnostics.status[0].message = "sdh initialized and running, tactile sensors not connected";
00795 }
00796 else
00797 {
00798 diagnostics.status[0].level = 1;
00799 diagnostics.status[0].name = nh_.getNamespace();
00800 diagnostics.status[0].message = "sdh not initialized";
00801 }
00802 }
00803
00804 topicPub_Diagnostics_.publish(diagnostics);
00805
00806 }
00807
00813 void updateDsa()
00814 {
00815 static const int dsa_reorder[6] = { 2 ,3, 4, 5, 0 , 1 };
00816 ROS_DEBUG("updateTactileData");
00817
00818 if(isDSAInitialized_)
00819 {
00820
00821 for(int i=0; i<7; i++)
00822 {
00823 try
00824 {
00825
00826 dsa_->UpdateFrame();
00827 }
00828 catch (SDH::cSDHLibraryException* e)
00829 {
00830 ROS_ERROR("An exception was caught: %s", e->what());
00831 delete e;
00832 }
00833 }
00834
00835 schunk_sdh::TactileSensor msg;
00836 msg.header.stamp = ros::Time::now();
00837 int m, x, y;
00838 msg.tactile_matrix.resize(dsa_->GetSensorInfo().nb_matrices);
00839 for ( int i = 0; i < dsa_->GetSensorInfo().nb_matrices; i++ )
00840 {
00841 m = dsa_reorder[i];
00842 schunk_sdh::TactileMatrix &tm = msg.tactile_matrix[i];
00843 tm.matrix_id = i;
00844 tm.cells_x = dsa_->GetMatrixInfo( m ).cells_x;
00845 tm.cells_y = dsa_->GetMatrixInfo( m ).cells_y;
00846 tm.tactile_array.resize(tm.cells_x * tm.cells_y);
00847 for ( y = 0; y < tm.cells_y; y++ )
00848 {
00849 for ( x = 0; x < tm.cells_x; x++ )
00850 tm.tactile_array[tm.cells_x*y + x] = dsa_->GetTexel( m, x, y );
00851 }
00852 }
00853
00854 topicPub_TactileSensor_.publish(msg);
00855 }
00856 }
00857 };
00858
00864 int main(int argc, char** argv)
00865 {
00866
00867 ros::init(argc, argv, "schunk_sdh");
00868
00869
00870 SdhNode sdh_node(ros::this_node::getName() + "/follow_joint_trajectory");
00871 if (!sdh_node.init()) return 0;
00872
00873 ROS_INFO("...sdh node running...");
00874
00875 double frequency;
00876 if (sdh_node.nh_.hasParam("frequency"))
00877 {
00878 sdh_node.nh_.getParam("frequency", frequency);
00879 }
00880 else
00881 {
00882 frequency = 5;
00883 ROS_WARN("Parameter frequency not available, setting to default value: %f Hz", frequency);
00884 }
00885
00886
00887 ros::Rate loop_rate(frequency);
00888 while(sdh_node.nh_.ok())
00889 {
00890
00891 sdh_node.updateSdh();
00892
00893
00894 sdh_node.updateDsa();
00895
00896
00897 ros::spinOnce();
00898 loop_rate.sleep();
00899 }
00900
00901 return 0;
00902 }
00903