00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00033 #include <phantom_control/omni.h>
00034 #include <phantom_control/conio.h>
00035
00036 #include <sys/types.h>
00037 #include <unistd.h>
00038 #include <stdlib.h>
00039
00040 #include <haptic_force/Force.h>
00041
00042 #include <phantom_control/State.h>
00043
00044 HDSchedulerHandle gCallbackHandle = 0;
00045 OmniState state;
00046 bool g_new=0;
00047 phantom_control::State g_SS;
00048
00049 hduVector3Dd g_home_pos(HOME_XX, HOME_YY, HOME_ZZ);
00050
00051 void ee_convert(void);
00052 void ForceCallBk ( const haptic_force::Force &force );
00053
00054 void HHD_Auto_Calibration(void);
00055 HDCallbackCode HDCALLBACK MonitorCallback(void *pUserData);
00056
00057 void SetHomePos(void);
00058
00059
00064 int main ( int argc, char **argv )
00065 {
00066
00067 OmniState *ss=&state;
00068
00069
00070
00071
00072
00073 HDErrorInfo error;
00074 HHD hHD = hdInitDevice(HD_DEFAULT_DEVICE);
00075
00076 if (HD_DEVICE_ERROR(error = hdGetError()))
00077 {
00078 hduPrintError(stderr, &error, "Failed to initialize haptic device");
00079 fprintf(stderr, "\nPress any key to quit.\n");
00080 getch();
00081 return -1;
00082 }
00083 ROS_INFO("Found %s.\n\n", hdGetString(HD_DEVICE_MODEL_TYPE));
00084
00085
00086
00087 gCallbackHandle = hdScheduleAsynchronous(MonitorCallback, ss, HD_MAX_SCHEDULER_PRIORITY);
00088
00089 hdEnable(HD_FORCE_OUTPUT);
00090
00091 hdStartScheduler();
00092 if (HD_DEVICE_ERROR(error = hdGetError()))
00093 {
00094 hduPrintError(stderr, &error, "Failed to start scheduler");
00095 fprintf(stderr, "\nPress any key to quit.\n");
00096 getch();
00097 return -1;
00098 }
00099
00100 HHD_Auto_Calibration();
00101
00102
00103
00104
00105
00106 ss->buttons[0] = 0;
00107 ss->buttons[1] = 0;
00108 ss->home_pos = g_home_pos;
00109 ss->home=0;
00110
00111
00112
00113
00114 ros::init( argc, argv, "phantom_node" );
00115
00116 ros::NodeHandle n("~");
00117
00118 ros::Publisher pub_state= n.advertise< phantom_control::State >( "/phantom_state", 1000 );
00119
00120 ros::Subscriber sub_force = n.subscribe ( "/force", 1000, ForceCallBk );
00121
00122 ros::Rate loop_rate( 2.5*1300 );
00123
00124 ee_convert();
00125
00126 int pid = getpid(), rpid;
00127
00128 boost::format fmt("sudo renice -10 %d");
00129 fmt % pid;
00130
00131 rpid = std::system(fmt.str().c_str());
00132
00133 while ( ros::ok () )
00134 {
00135 if(g_new)
00136 {
00137 ee_convert();
00138
00139 pub_state.publish( g_SS );
00140
00141 g_new=0;
00142 }
00143
00144
00145
00146
00147 if(g_SS.buttons[1])
00148 {
00149 g_home_pos[0]=g_SS.position[0];
00150 g_home_pos[1]=g_SS.position[1];
00151 g_home_pos[2]=g_SS.position[2];
00152 ss->home_pos[0]=g_SS.position[0];
00153 ss->home_pos[1]=g_SS.position[1];
00154 ss->home_pos[2]=g_SS.position[2];
00155 }
00156
00157 ros::spinOnce ( );
00158
00159 loop_rate.sleep ( );
00160 }
00161
00162
00163 ROS_INFO("Ending Session....\n");
00164 hdStopScheduler();
00165 hdUnschedule(gCallbackHandle);
00166 hdDisableDevice(hHD);
00167
00168 return 0;
00169 }
00170
00177 void ee_convert(void)
00178 {
00179
00180 OmniState *ss=&state;
00181
00182 g_SS.pos_hist1[0]=g_SS.position[0];
00183 g_SS.pos_hist1[1]=g_SS.position[1];
00184 g_SS.pos_hist1[2]=g_SS.position[2];
00185
00186 g_SS.position[0]=ss->position[0];
00187 g_SS.position[1]=ss->position[1];
00188 g_SS.position[2]=ss->position[2];
00189
00190 g_SS.rot[0]=ss->rot[0];
00191 g_SS.rot[1]=ss->rot[1];
00192 g_SS.rot[2]=ss->rot[2];
00193
00194 g_SS.joints[0]=ss->joints[0];
00195 g_SS.joints[1]=ss->joints[1];
00196 g_SS.joints[2]=ss->joints[2];
00197
00198 g_SS.temp[0]=ss->temp[0];
00199 g_SS.temp[1]=ss->temp[1];
00200 g_SS.temp[2]=ss->temp[2];
00201
00202 g_SS.buttons[0]=ss->buttons[0];
00203 g_SS.buttons[1]=ss->buttons[1];
00204
00205 g_SS.home=ss->home;
00206
00207 g_SS.home_pos[0]=ss->home_pos[0];
00208 g_SS.home_pos[1]=ss->home_pos[1];
00209 g_SS.home_pos[2]=ss->home_pos[2];
00210
00211 g_SS.force[0]=ss->force[0];
00212 g_SS.force[1]=ss->force[1];
00213 g_SS.force[2]=ss->force[2];
00214
00215 g_SS.header.stamp = ros::Time::now ( );
00216 }
00217
00224 void ForceCallBk ( const haptic_force::Force &force )
00225 {
00226 state.force[0]=force.force[0];
00227 state.force[1]=force.force[1];
00228 state.force[2]=force.force[2];
00229 }
00230
00237 void HHD_Auto_Calibration(void)
00238 {
00239 int calibrationStyle;
00240 int supportedCalibrationStyles;
00241 HDErrorInfo error;
00242
00243 hdGetIntegerv(HD_CALIBRATION_STYLE, &supportedCalibrationStyles);
00244 if (supportedCalibrationStyles & HD_CALIBRATION_ENCODER_RESET)
00245 {
00246 calibrationStyle = HD_CALIBRATION_ENCODER_RESET;
00247 ROS_INFO("HD_CALIBRATION_ENCODER_RESE..\n\n");
00248 }
00249 if (supportedCalibrationStyles & HD_CALIBRATION_INKWELL)
00250 {
00251 calibrationStyle = HD_CALIBRATION_INKWELL;
00252 ROS_INFO("HD_CALIBRATION_INKWELL..\n\n");
00253 }
00254 if (supportedCalibrationStyles & HD_CALIBRATION_AUTO)
00255 {
00256 calibrationStyle = HD_CALIBRATION_AUTO;
00257 ROS_INFO("HD_CALIBRATION_AUTO..\n\n");
00258 }
00259
00260 do
00261 {
00262 hdUpdateCalibration(calibrationStyle);
00263 ROS_INFO("Calibrating.. (put stylus in well)\n");
00264 if (HD_DEVICE_ERROR(error = hdGetError()))
00265 {
00266 hduPrintError(stderr, &error, "Reset encoders reset failed.");
00267 break;
00268 }
00269 } while (hdCheckCalibration() != HD_CALIBRATION_OK);
00270
00271 ROS_INFO("...\n...\nCalibration complete.\n");
00272 }
00273
00280 HDCallbackCode HDCALLBACK MonitorCallback(void *pUserData)
00281 {
00282 OmniState *omni_state = static_cast<OmniState *>(pUserData);
00283
00284 HDErrorInfo error;
00285
00286 int nButtons = 0;
00287
00288 hduVector3Dd position;
00289 hduVector3Dd force;
00290
00291 omni_state->force=state.force;
00292
00293 hdBeginFrame(hdGetCurrentDevice());
00294
00295 hdGetDoublev(HD_CURRENT_GIMBAL_ANGLES, omni_state->rot);
00296 hdGetDoublev(HD_CURRENT_POSITION, omni_state->position);
00297 hdGetDoublev(HD_CURRENT_JOINT_ANGLES, omni_state->joints);
00298
00299
00300 hdGetIntegerv(HD_CURRENT_BUTTONS, &nButtons);
00301 omni_state->buttons[0] = (nButtons & HD_DEVICE_BUTTON_1) ? 1 : 0;
00302 omni_state->buttons[1] = (nButtons & HD_DEVICE_BUTTON_2) ? 1 : 0;
00303
00304
00305 hdGetDoublev(HD_MOTOR_TEMPERATURE, omni_state->temp);
00306
00307 if(omni_state->buttons[0]!=1)
00308 {
00309 SetHomePos();
00310 }
00311 else
00312 {
00313 hdSetDoublev(HD_CURRENT_FORCE, omni_state->force);
00314 omni_state->home=0;
00315 }
00316
00317 hdEndFrame(hdGetCurrentDevice());
00318
00319 if (HD_DEVICE_ERROR(error = hdGetError()))
00320 {
00321 hduPrintError(stderr, &error, "Error during main scheduler callback\n");
00322 if (hduIsSchedulerError(&error))
00323 return HD_CALLBACK_DONE;
00324 }
00325
00326
00327 float t[7] = {0.0, omni_state->joints[0], omni_state->joints[1], omni_state->joints[2]-omni_state->joints[1], omni_state->rot[0], omni_state->rot[1], omni_state->rot[2]};
00328
00329 for (int i = 0; i < 7; i++) omni_state->thetas[i] = t[i];
00330
00331 g_new=1;
00332
00333 return HD_CALLBACK_CONTINUE;
00334 }
00335
00336
00343 void SetHomePos(void)
00344 {
00345 hduVector3Dd home_pos = g_home_pos;
00346 hduVector3Dd position;
00347
00348 position[0]=g_SS.position[0];
00349 position[1]=g_SS.position[1];
00350 position[2]=g_SS.position[2];
00351
00352 if( g_SS.position == g_SS.home_pos)
00353 {
00354 g_SS.home=1;
00355 hduVector3Dd force2home(0, 0.49, 0);
00356
00357 hdSetDoublev(HD_CURRENT_FORCE, force2home);
00358 }
00359 if(!g_SS.home)
00360 {
00361 hduVector3Dd force2home = (home_pos - position);
00362 force2home.normalize();
00363 force2home*=0.975;
00364
00365 hdSetDoublev(HD_CURRENT_FORCE, force2home);
00366 }
00367
00368 }