Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007  
00008 
00009 
00010 
00011 
00012 
00013         
00014         
00015         
00016 
00017 
00018 
00019  
00020 #include <iostream>
00021 #include <boost/thread/thread.hpp>
00022 #include <boost/date_time.hpp>
00023 #include <boost/thread/locks.hpp>
00024 
00025 #include "ros/ros.h"
00026 #include "ros/service.h"
00027 #include "ros/service_server.h"
00028 #include "sensor_msgs/JointState.h"
00029 #include "std_msgs/String.h"
00030 
00031 #include <stdio.h>
00032 #include <iostream>
00033 #include <string>
00034 
00035 
00036 #include "controlAllegroHand.h"
00037 
00038 
00039 #define JOINT_STATE_TOPIC "/allegroHand/joint_states"
00040 #define JOINT_CMD_TOPIC "/allegroHand/joint_cmd"
00041 #define EXT_CMD_TOPIC "/allegroHand/external_cmd"
00042 
00043 #define JOINT_DESIRED_TOPIC "/allegroHand/joint_desired_states"
00044 #define JOINT_CURRENT_TOPIC "/allegroHand/joint_current_states"
00045 
00046 
00047 double desired_position[DOF_JOINTS]                             = {0.0};
00048 double current_position[DOF_JOINTS]                     = {0.0};
00049 double previous_position[DOF_JOINTS]                    = {0.0};
00050 double current_position_filtered[DOF_JOINTS]    = {0.0};
00051 double previous_position_filtered[DOF_JOINTS]   = {0.0};
00052 
00053 double desired_velocity[DOF_JOINTS]                             = {0.0};
00054 double current_velocity[DOF_JOINTS]                     = {0.0};
00055 double previous_velocity[DOF_JOINTS]                    = {0.0};
00056 double current_velocity_filtered[DOF_JOINTS]    = {0.0};
00057 
00058 double desired_torque[DOF_JOINTS]                               = {0.0};
00059 
00060 
00061 std::string jointNames[DOF_JOINTS]      = {    "joint_0.0",    "joint_1.0",    "joint_2.0",   "joint_3.0" , 
00062                                                                                    "joint_4.0",    "joint_5.0",    "joint_6.0",   "joint_7.0" , 
00063                                                                                    "joint_8.0",    "joint_9.0",    "joint_10.0",  "joint_11.0", 
00064                                                                                    "joint_12.0",   "joint_13.0",   "joint_14.0",  "joint_15.0" };
00065 
00066 int frame = 0;
00067 
00068 
00069 int lEmergencyStop = 0;
00070 
00071 boost::mutex *mutex;
00072 
00073 
00074 ros::Publisher joint_state_pub;
00075 ros::Publisher joint_desired_state_pub;
00076 ros::Publisher joint_current_state_pub;
00077 
00078 ros::Subscriber joint_cmd_sub;                          
00079 ros::Subscriber external_cmd_sub;                       
00080 sensor_msgs::JointState msgJoint_desired;       
00081 sensor_msgs::JointState msgJoint_current;       
00082 sensor_msgs::JointState msgJoint;                       
00083 std::string  ext_cmd;
00084 
00085 
00086 ros::Time tstart;
00087 ros::Time tnow;
00088 double secs;
00089 double dt;
00090 
00091 
00092 controlAllegroHand *canDevice;
00093 
00094 
00095 
00096 
00097 void SetjointCallback(const sensor_msgs::JointState& msg)
00098 {
00099         mutex->lock();
00100         for(int i=0;i<DOF_JOINTS;i++) desired_position[i] = msg.position[i];
00101         mutex->unlock();        
00102 }
00103 
00104 
00105 void extCmdCallback(const std_msgs::String::ConstPtr& msg)
00106 {
00107         ROS_INFO("CTRL: Processing external command");
00108         ext_cmd = msg->data.c_str();
00109 
00110         
00111         if (ext_cmd.compare("comparisonString") == 0)
00112         {
00113                 
00114         }    
00115         else
00116         {
00117                 
00118         }       
00119 }
00120 
00121 
00122 
00123 void timerCallback(const ros::TimerEvent& event)
00124 {
00125         
00126         tnow = ros::Time::now();
00127         dt = 1e-9*(tnow - tstart).nsec;
00128         tstart = tnow;
00129                 
00130         
00131         for(int i=0; i<DOF_JOINTS; i++) previous_position[i] = current_position[i];
00132                 
00133                 
00134                 
00135                 
00136 
00137 
00138         
00139         canDevice->setTorque(desired_torque);           
00140         lEmergencyStop = canDevice->update();           
00141         canDevice->getJointInfo(current_position);      
00142 
00143                 
00144                 
00145                                 
00146         
00147         if( lEmergencyStop < 0 )
00148         {
00149                 ROS_ERROR("\n\nAllegro Hand Node is Shutting Down! (Emergency Stop)\n");
00150                 ros::shutdown();
00151         }
00152 
00153 
00154 
00155 
00156 
00157         for(int i=0; i<DOF_JOINTS; i++)    
00158         {
00159                 current_position_filtered[i] = (0.6*current_position_filtered[i]) + (0.198*previous_position[i]) + (0.198*current_position[i]);
00160                 current_velocity[i] = (current_position_filtered[i] - previous_position_filtered[i]) / dt;
00161                 current_velocity_filtered[i] = (0.6*current_velocity_filtered[i]) + (0.198*previous_velocity[i]) + (0.198*current_velocity[i]);
00162         }       
00163 
00164 
00165 
00166 
00167 
00168     if(frame>100) 
00169         {
00170 
00171 
00172 
00173     
00174 
00175         }
00176 
00177 
00178 
00179 
00180 
00181         
00182         msgJoint.header.stamp           = tnow; 
00183         for(int i=0; i<DOF_JOINTS; i++)
00184         {
00185                 msgJoint.position[i]    = current_position_filtered[i];
00186                 msgJoint.velocity[i]    = current_velocity_filtered[i];
00187                 msgJoint.effort[i]              = desired_torque[i];
00188         }
00189         joint_state_pub.publish(msgJoint);
00190                 
00191                 
00192         frame++;
00193 
00194 } 
00195 
00196 
00197 
00198 
00199 
00200 
00201 
00202 
00203 int main(int argc, char** argv)
00204 {
00205         using namespace std;
00206         
00207         ros::init(argc, argv, "allegro_hand_core");
00208         ros::Time::init();
00209         
00210         ros::NodeHandle nh;
00211 
00212         
00213         ros::Timer timer = nh.createTimer(ros::Duration(0.003), timerCallback);
00214 
00215         mutex = new boost::mutex();
00216 
00217         
00218         joint_state_pub = nh.advertise<sensor_msgs::JointState>(JOINT_STATE_TOPIC, 3);
00219         joint_cmd_sub = nh.subscribe(JOINT_CMD_TOPIC, 3, SetjointCallback);
00220         external_cmd_sub = nh.subscribe(EXT_CMD_TOPIC, 1, extCmdCallback);
00221         
00222         
00223         msgJoint.position.resize(DOF_JOINTS);
00224         msgJoint.velocity.resize(DOF_JOINTS);
00225         msgJoint.effort.resize(DOF_JOINTS);
00226         msgJoint.name.resize(DOF_JOINTS);
00227 
00228         
00229         for(int i=0; i<DOF_JOINTS; i++) msgJoint.name[i] = jointNames[i];       
00230 
00231         
00232         
00233         
00234         string robot_name, whichHand, manufacturer, origin, serial;
00235         double version;
00236         ros::param::get("~hand_info/robot_name",robot_name);
00237         ros::param::get("~hand_info/which_hand",whichHand);
00238         ros::param::get("~hand_info/manufacturer",manufacturer);
00239         ros::param::get("~hand_info/origin",origin);
00240         ros::param::get("~hand_info/serial",serial);
00241         ros::param::get("~hand_info/version",version);
00242         
00243 
00244         
00245         canDevice = new controlAllegroHand();
00246         canDevice->init();
00247         usleep(3000);
00248         
00249         
00250         cout << endl << endl << robot_name << " v" << version << endl << serial << " (" << whichHand << ")" << endl << manufacturer << endl << origin << endl << endl;
00251 
00252         
00253         for(int i=0; i<16; i++) desired_torque[i] = 0.0;
00254 
00255         
00256         tstart = ros::Time::now();
00257 
00258         
00259         ros::spin();                    
00260 
00261         
00262         nh.shutdown();
00263         delete canDevice;
00264         printf("\nAllegro Hand Node has been shut down. Bye!\n\n");
00265         return 0;
00266         
00267 }
00268 
00269