Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include <iostream>
00012 #include <boost/thread/thread.hpp>
00013 #include <boost/date_time.hpp>
00014 #include <boost/thread/locks.hpp>
00015
00016 #include "ros/ros.h"
00017 #include "ros/service.h"
00018 #include "ros/service_server.h"
00019 #include "sensor_msgs/JointState.h"
00020 #include "std_msgs/String.h"
00021
00022 #include <stdio.h>
00023 #include <iostream>
00024 #include <string>
00025
00026 #include "BHand/BHand.h"
00027 #include "controlAllegroHand.h"
00028
00029
00030 #define JOINT_STATE_TOPIC "/allegroHand/joint_states"
00031 #define JOINT_CMD_TOPIC "/allegroHand/joint_cmd"
00032 #define LIB_CMD_TOPIC "/allegroHand/lib_cmd"
00033
00034
00035 double desired_position[DOF_JOINTS] = {0.0};
00036 double current_position[DOF_JOINTS] = {0.0};
00037 double previous_position[DOF_JOINTS] = {0.0};
00038 double current_position_filtered[DOF_JOINTS] = {0.0};
00039 double previous_position_filtered[DOF_JOINTS] = {0.0};
00040
00041 double current_velocity[DOF_JOINTS] = {0.0};
00042 double previous_velocity[DOF_JOINTS] = {0.0};
00043 double current_velocity_filtered[DOF_JOINTS] = {0.0};
00044
00045 double desired_torque[DOF_JOINTS] = {0.0};
00046
00047 std::string lib_cmd;
00048
00049
00050 std::string jointNames[DOF_JOINTS] = { "joint_0.0", "joint_1.0", "joint_2.0", "joint_3.0" ,
00051 "joint_4.0", "joint_5.0", "joint_6.0", "joint_7.0" ,
00052 "joint_8.0", "joint_9.0", "joint_10.0", "joint_11.0",
00053 "joint_12.0", "joint_13.0", "joint_14.0", "joint_15.0" };
00054
00055 int frame = 0;
00056
00057
00058 bool lIsBegin = false;
00059 bool pdControl = true;
00060 int lEmergencyStop = 0;
00061
00062 boost::mutex *mutex;
00063
00064
00065 ros::Publisher joint_state_pub;
00066 ros::Subscriber joint_cmd_sub;
00067 ros::Subscriber lib_cmd_sub;
00068 sensor_msgs::JointState msgJoint;
00069
00070
00071 ros::Time tstart;
00072 ros::Time tnow;
00073 double secs;
00074 double dt;
00075
00076
00077 eMotionType gMotionType = eMotionType_NONE ;
00078 BHand* pBHand = NULL;
00079
00080
00081
00082 controlAllegroHand* canDevice;
00083
00084
00085
00086
00087 void SetjointCallback(const sensor_msgs::JointState& msg)
00088 {
00089
00090 pdControl=true;
00091
00092 mutex->lock();
00093 for(int i=0;i<DOF_JOINTS;i++) desired_position[i] = msg.position[i];
00094 mutex->unlock();
00095
00096 pBHand->SetMotionType(eMotionType_JOINT_PD);
00097 }
00098
00099 void libCmdCallback(const std_msgs::String::ConstPtr& msg)
00100 {
00101 ROS_INFO("CTRL: Heard: [%s]", msg->data.c_str());
00102 lib_cmd = msg->data.c_str();
00103
00104
00105
00106 if (lib_cmd.compare("pdControl") == 0)
00107 {
00108 pBHand->SetMotionType(eMotionType_JOINT_PD);
00109 pdControl = true;
00110 }
00111 else
00112 pdControl = false;
00113
00114 if (lib_cmd.compare("home") == 0)
00115 pBHand->SetMotionType(eMotionType_HOME);
00116
00117 if (lib_cmd.compare("ready") == 0)
00118 pBHand->SetMotionType(eMotionType_READY);
00119
00120 if (lib_cmd.compare("grasp_3") == 0)
00121 pBHand->SetMotionType(eMotionType_GRASP_3);
00122
00123 if (lib_cmd.compare("grasp_4") == 0)
00124 pBHand->SetMotionType(eMotionType_GRASP_4);
00125
00126 if (lib_cmd.compare("pinch_it") == 0)
00127 pBHand->SetMotionType(eMotionType_PINCH_IT);
00128
00129 if (lib_cmd.compare("pinch_mt") == 0)
00130 pBHand->SetMotionType(eMotionType_PINCH_MT);
00131
00132 if (lib_cmd.compare("envelop") == 0)
00133 pBHand->SetMotionType(eMotionType_ENVELOP);
00134
00135 if (lib_cmd.compare("off") == 0)
00136 pBHand->SetMotionType(eMotionType_NONE);
00137
00138 if (lib_cmd.compare("save") == 0)
00139 for(int i=0; i<DOF_JOINTS; i++) desired_position[i] = current_position[i];
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155 }
00156
00157
00158 void timerCallback(const ros::TimerEvent& event)
00159 {
00160
00161 tnow = ros::Time::now();
00162 dt = 1e-9*(tnow - tstart).nsec;
00163 tstart = tnow;
00164
00165
00166 for(int i=0; i<DOF_JOINTS; i++)
00167 {
00168 previous_position[i] = current_position[i];
00169 previous_position_filtered[i] = current_position_filtered[i];
00170 previous_velocity[i] = current_velocity[i];
00171 }
00172
00173
00174
00175
00176 canDevice->setTorque(desired_torque);
00177 lEmergencyStop = canDevice->update();
00178 canDevice->getJointInfo(current_position);
00179
00180
00181
00182
00183
00184
00185 for(int i=0; i<DOF_JOINTS; i++)
00186 {
00187 current_position_filtered[i] = (0.6*current_position_filtered[i]) + (0.198*previous_position[i]) + (0.198*current_position[i]);
00188 current_velocity[i] = (current_position_filtered[i] - previous_position_filtered[i]) / dt;
00189 current_velocity_filtered[i] = (0.6*current_velocity_filtered[i]) + (0.198*previous_velocity[i]) + (0.198*current_velocity[i]);
00190 }
00191
00192
00193 if( lEmergencyStop < 0 )
00194 {
00195
00196
00197 ROS_ERROR("\n\nAllegro Hand Node is Shutting Down! (Emergency Stop)\n");
00198 ros::shutdown();
00199 }
00200
00201
00202 pBHand->SetJointPosition(current_position_filtered);
00203
00204
00205 if( lIsBegin == false ){
00206 if(frame > 10){
00207 mutex->lock();
00208 for(int i=0; i<DOF_JOINTS; i++) desired_position[i] = current_position[i];
00209 mutex->unlock();
00210
00211 lIsBegin = true;
00212 }
00213
00214
00215
00216
00217
00218
00219 pBHand->SetMotionType(eMotionType_NONE);
00220
00221 pBHand->UpdateControl((double)frame*ALLEGRO_CONTROL_TIME_INTERVAL);
00222 for(int i=0; i<DOF_JOINTS; i++) desired_torque[i] = 0.0;
00223 }
00224 else{
00225
00226
00227
00228
00229
00230
00231
00232 if (pdControl==true)
00233 pBHand->SetJointDesiredPosition(desired_position);
00234
00235
00236 pBHand->UpdateControl((double)frame*ALLEGRO_CONTROL_TIME_INTERVAL);
00237
00238
00239 pBHand->GetJointTorque(desired_torque);
00240
00241
00242 for(int i=0; i<DOF_JOINTS; i++)
00243 current_velocity[i] = (current_position[i] - previous_position[i])/dt;
00244
00245
00246 msgJoint.header.stamp = tnow;
00247 for(int i=0; i<DOF_JOINTS; i++) msgJoint.position[i] = current_position_filtered[i];
00248 for(int i=0; i<DOF_JOINTS; i++) msgJoint.velocity[i] = current_velocity_filtered[i];
00249 for(int i=0; i<DOF_JOINTS; i++) msgJoint.effort[i] = desired_torque[i];
00250 joint_state_pub.publish(msgJoint);
00251 }
00252
00253 frame++;
00254 }
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264 int main(int argc, char** argv)
00265 {
00266 using namespace std;
00267
00268 ros::init(argc, argv, "allegro_hand_core_grasp");
00269 ros::Time::init();
00270
00271 ros::NodeHandle nh;
00272
00273
00274 ros::Timer timer = nh.createTimer(ros::Duration(0.003), timerCallback);
00275
00276 mutex = new boost::mutex();
00277
00278
00279 joint_state_pub = nh.advertise<sensor_msgs::JointState>(JOINT_STATE_TOPIC, 3);
00280 joint_cmd_sub = nh.subscribe(JOINT_CMD_TOPIC, 3, SetjointCallback);
00281 lib_cmd_sub = nh.subscribe(LIB_CMD_TOPIC, 1, libCmdCallback);
00282
00283
00284 msgJoint.position.resize(DOF_JOINTS);
00285 msgJoint.velocity.resize(DOF_JOINTS);
00286 msgJoint.effort.resize(DOF_JOINTS);
00287 msgJoint.name.resize(DOF_JOINTS);
00288
00289
00290 for(int i=0; i<DOF_JOINTS; i++) msgJoint.name[i] = jointNames[i];
00291
00292
00293
00294
00295 string robot_name, whichHand, manufacturer, origin, serial;
00296 double version;
00297 ros::param::get("~hand_info/robot_name",robot_name);
00298 ros::param::get("~hand_info/which_hand",whichHand);
00299 ros::param::get("~hand_info/manufacturer",manufacturer);
00300 ros::param::get("~hand_info/origin",origin);
00301 ros::param::get("~hand_info/serial",serial);
00302 ros::param::get("~hand_info/version",version);
00303
00304
00305 if (whichHand.compare("left") == 0)
00306 {
00307 pBHand = new BHand(eHandType_Left);
00308 ROS_WARN("CTRL: Left Allegro Hand controller initialized.");
00309 }
00310 else
00311 {
00312 pBHand = new BHand(eHandType_Right);
00313 ROS_WARN("CTRL: Right Allegro Hand controller initialized.");
00314 }
00315 pBHand->SetTimeInterval(ALLEGRO_CONTROL_TIME_INTERVAL);
00316
00317
00318 canDevice = new controlAllegroHand();
00319 canDevice->init();
00320 usleep(3000);
00321
00322
00323 cout << endl << endl << robot_name << " v" << version << endl << serial << " (" << whichHand << ")" << endl << manufacturer << endl << origin << endl << endl;
00324
00325
00326
00327 for(int i=0; i<16; i++) desired_torque[i] = 0.0;
00328
00329
00330 lIsBegin = false;
00331
00332
00333 tstart = ros::Time::now();
00334
00335
00336 ros::spin();
00337
00338
00339
00340
00341
00342
00343 nh.shutdown();
00344 delete canDevice;
00345 delete pBHand;
00346
00347 printf("\nAllegro Hand Node has been shut down. Bye!\n\n");
00348 return 0;
00349 }
00350
00351