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


schunk_sdh
Author(s): Florian Weisshardt
autogenerated on Mon Oct 6 2014 07:29:15