00001 #include <iostream>
00002 #include <cstdio>
00003 #include <cstdlib>
00004 #include <string>
00005 #include <cassert>
00006 #include <cmath>
00007
00008 #include <HD/hd.h>
00009 #include <HDU/hduVector.h>
00010 #include <HDU/hduMatrix.h>
00011 #include <HDU/hduError.h>
00012
00013 #include <ros/ros.h>
00014 #include <std_msgs/Float64.h>
00015 #include <sensor_msgs/JointState.h>
00016 #include <vrep_common/JointSetStateData.h>
00017 #include <vrep_common/ForceSensorData.h>
00018 #include <vrep_common/ObjectGroupData.h>
00019 #include <vrep_common/simRosGetObjectHandle.h>
00020 #include <phantom_dual/conio.h>
00021
00022 using namespace std;
00023
00024 typedef struct
00025 {
00026 HDdouble angle[3];
00027 HDdouble torque[3];
00028
00029 } omni_state;
00030
00031 omni_state omni;
00032
00033 vrep_common::JointSetStateData joint_target;
00034 vrep_common::simRosGetObjectHandle object_handles;
00035
00036 ros::ServiceClient object_handles_srv;
00037 ros::Publisher command_joints_position_pub;
00038
00039 int left_joint1Handle;
00040 int left_joint2Handle;
00041 int left_joint3Handle;
00042 int left_joint4Handle;
00043 int left_joint5Handle;
00044 int left_joint6Handle;
00045 int right_joint1Handle;
00046 int right_joint2Handle;
00047 int right_joint3Handle;
00048 int right_joint4Handle;
00049 int right_joint5Handle;
00050 int right_joint6Handle;
00051
00052 int left_sensor1Handle;
00053 int left_sensor2Handle;
00054 int left_sensor3Handle;
00055 int left_sensor4Handle;
00056 int right_sensor1Handle;
00057
00058 HDSchedulerHandle gCallbackHandle = HD_INVALID_HANDLE;
00059
00060 HDdouble base_torque[3];
00061
00062
00063 HDCallbackCode HDCALLBACK ServoSchedulerCallback(void *pUserData)
00064 {
00065 HDErrorInfo error;
00066
00067 hdBeginFrame(hdGetCurrentDevice());
00068
00069 hdGetDoublev(HD_CURRENT_JOINT_ANGLES, omni.angle);
00070 hdSetDoublev(HD_CURRENT_JOINT_TORQUE, base_torque);
00071
00072 hdEndFrame(hdGetCurrentDevice());
00073
00074
00075
00076 if (HD_DEVICE_ERROR(error = hdGetError()))
00077 {
00078 hduPrintError(stderr, &error, "Error during main scheduler callback\n");
00079 if (hduIsSchedulerError(&error))
00080 return HD_CALLBACK_DONE;
00081 }
00082
00083 return HD_CALLBACK_CONTINUE;
00084 }
00085
00086
00087 void objectHandles()
00088 {
00089 object_handles.request.objectName = "left_joint1";
00090 if (object_handles_srv.call(object_handles))
00091 left_joint1Handle = object_handles.response.handle;
00092 else
00093 ROS_ERROR("Failed to call service get_joint_handles");
00094
00095 object_handles.request.objectName = "left_joint2";
00096 if (object_handles_srv.call(object_handles))
00097 left_joint2Handle = object_handles.response.handle;
00098 else
00099 ROS_ERROR("Failed to call service get_joint_handles");
00100
00101 object_handles.request.objectName = "left_joint3";
00102 if (object_handles_srv.call(object_handles))
00103 left_joint3Handle = object_handles.response.handle;
00104 else
00105 ROS_ERROR("Failed to call service get_joint_handles");
00106
00107 object_handles.request.objectName = "left_joint4";
00108 if (object_handles_srv.call(object_handles))
00109 left_joint4Handle = object_handles.response.handle;
00110 else
00111 ROS_ERROR("Failed to call service get_joint_handles");
00112
00113 object_handles.request.objectName = "left_joint5";
00114 if (object_handles_srv.call(object_handles))
00115 left_joint5Handle = object_handles.response.handle;
00116 else
00117 ROS_ERROR("Failed to call service get_joint_handles");
00118
00119 object_handles.request.objectName = "left_joint6";
00120 if (object_handles_srv.call(object_handles))
00121 left_joint6Handle = object_handles.response.handle;
00122 else
00123 ROS_ERROR("Failed to call service get_joint_handles");
00124
00125
00126 object_handles.request.objectName = "right_joint1";
00127 if (object_handles_srv.call(object_handles))
00128 right_joint1Handle = object_handles.response.handle;
00129 else
00130 ROS_ERROR("Failed to call service get_joint_handles");
00131
00132 object_handles.request.objectName = "right_joint2";
00133 if (object_handles_srv.call(object_handles))
00134 right_joint2Handle = object_handles.response.handle;
00135 else
00136 ROS_ERROR("Failed to call service get_joint_handles");
00137
00138 object_handles.request.objectName = "right_joint3";
00139 if (object_handles_srv.call(object_handles))
00140 right_joint3Handle = object_handles.response.handle;
00141 else
00142 ROS_ERROR("Failed to call service get_joint_handles");
00143
00144 object_handles.request.objectName = "right_joint4";
00145 if (object_handles_srv.call(object_handles))
00146 right_joint4Handle = object_handles.response.handle;
00147 else
00148 ROS_ERROR("Failed to call service get_joint_handles");
00149
00150 object_handles.request.objectName = "right_joint5";
00151 if (object_handles_srv.call(object_handles))
00152 right_joint5Handle = object_handles.response.handle;
00153 else
00154 ROS_ERROR("Failed to call service get_joint_handles");
00155
00156 object_handles.request.objectName = "right_joint6";
00157 if (object_handles_srv.call(object_handles))
00158 right_joint6Handle = object_handles.response.handle;
00159 else
00160 ROS_ERROR("Failed to call service get_joint_handles");
00161
00162
00163 object_handles.request.objectName = "left_sensor1";
00164 if (object_handles_srv.call(object_handles))
00165 left_sensor1Handle = object_handles.response.handle;
00166 else
00167 ROS_ERROR("Failed to call service get_joint_handles");
00168
00169 object_handles.request.objectName = "left_sensor2";
00170 if (object_handles_srv.call(object_handles))
00171 left_sensor2Handle = object_handles.response.handle;
00172 else
00173 ROS_ERROR("Failed to call service get_joint_handles");
00174
00175 object_handles.request.objectName = "left_sensor3";
00176 if (object_handles_srv.call(object_handles))
00177 left_sensor3Handle = object_handles.response.handle;
00178 else
00179 ROS_ERROR("Failed to call service get_joint_handles");
00180
00181 object_handles.request.objectName = "left_sensor4";
00182 if (object_handles_srv.call(object_handles))
00183 left_sensor4Handle = object_handles.response.handle;
00184 else
00185 ROS_ERROR("Failed to call service get_joint_handles");
00186
00187 object_handles.request.objectName = "right_sensor1";
00188 if (object_handles_srv.call(object_handles))
00189 right_sensor1Handle = object_handles.response.handle;
00190 else
00191 ROS_ERROR("Failed to call service get_joint_handles");
00192
00193
00194
00195
00196
00197
00198
00199 }
00200
00201
00202 void setJointValue()
00203 {
00204 joint_target.handles.data.clear();
00205 joint_target.setModes.data.clear();
00206 joint_target.values.data.clear();
00207
00208 joint_target.handles.data.push_back(left_joint2Handle);
00209 joint_target.setModes.data.push_back(1);
00210 joint_target.values.data.push_back(omni.angle[0]);
00211 joint_target.handles.data.push_back(right_joint2Handle);
00212 joint_target.setModes.data.push_back(1);
00213 joint_target.values.data.push_back(-omni.angle[0]);
00214
00215 joint_target.handles.data.push_back(left_joint6Handle);
00216 joint_target.setModes.data.push_back(1);
00217 joint_target.values.data.push_back(-omni.angle[0]);
00218 joint_target.handles.data.push_back(right_joint6Handle);
00219 joint_target.setModes.data.push_back(1);
00220 joint_target.values.data.push_back(omni.angle[0]);
00221
00222 joint_target.handles.data.push_back(left_joint4Handle);
00223 joint_target.setModes.data.push_back(1);
00224 joint_target.values.data.push_back((omni.angle[2]-(M_PI/2)));
00225 joint_target.handles.data.push_back(right_joint4Handle);
00226 joint_target.setModes.data.push_back(1);
00227 joint_target.values.data.push_back((omni.angle[2]-(M_PI/2)));
00228
00229 joint_target.handles.data.push_back(left_joint5Handle);
00230 joint_target.setModes.data.push_back(1);
00231 joint_target.values.data.push_back((omni.angle[2]-(M_PI/2)));
00232 joint_target.handles.data.push_back(right_joint5Handle);
00233 joint_target.setModes.data.push_back(1);
00234 joint_target.values.data.push_back((omni.angle[2]-(M_PI/2)));
00235
00236
00237
00238
00239
00240
00241
00242
00243 command_joints_position_pub.publish(joint_target);
00244 }
00245
00246
00247 void jointsCallback(const sensor_msgs::JointState& msg)
00248 {
00249 int scale_cte = 2700;
00250
00251 base_torque[0] = scale_cte*msg.position[1];
00252
00253 cout << "Balance angle: " << -msg.position[1]*(180/M_PI) << "\n" << endl;
00254 }
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271 void sensorsCallback(const vrep_common::ObjectGroupData& msg)
00272 {
00273 cout << "Left sensor 1 value: " << msg.floatData.data[2] << endl;
00274 cout << "Left sensor 2 value: " << msg.floatData.data[8] << endl;
00275 cout << "Left sensor 3 value: " << msg.floatData.data[14] << endl;
00276 cout << "Left sensor 4 value: " << msg.floatData.data[20] << endl;
00277
00278 cout << "Right sensor 1 value: " << msg.floatData.data[26] << endl;
00279
00280 cout << "--------------------------------------" << endl;
00281 }
00282
00283
00284 int main(int argc, char **argv)
00285 {
00286 HDErrorInfo error;
00287 HHD hHD = hdInitDevice(HD_DEFAULT_DEVICE);
00288 if (HD_DEVICE_ERROR(error = hdGetError()))
00289 {
00290 hduPrintError(stderr, &error, "Failed to initialize the device");
00291
00292 fprintf(stderr, "\nPress any key to quit.\n");
00293 getch();
00294 return -1;
00295 }
00296 ROS_INFO("Found %s.\n\n", hdGetString(HD_DEVICE_MODEL_TYPE));
00297
00298 gCallbackHandle = hdScheduleAsynchronous(ServoSchedulerCallback, 0, HD_MAX_SCHEDULER_PRIORITY);
00299 if (HD_DEVICE_ERROR(error = hdGetError()))
00300 {
00301 hduPrintError(stderr, &error, "Failed to schedule servoloop callback");
00302
00303 hdDisableDevice(hHD);
00304
00305 fprintf(stderr, "\nPress any key to quit.\n");
00306 getch();
00307 return -1;
00308 }
00309
00310 hdEnable(HD_FORCE_OUTPUT);
00311
00312 hdStartScheduler();
00313 if (HD_DEVICE_ERROR(error = hdGetError()))
00314 {
00315 hduPrintError(stderr, &error, "Failed to start the scheduler");
00316
00317 fprintf(stderr, "\nPress any key to quit.\n");
00318 getch();
00319 return -1;
00320 }
00321
00322 ros::init(argc, argv, "phantom_dual");
00323
00324 ros::NodeHandle n;
00325
00326 object_handles_srv = n.serviceClient<vrep_common::simRosGetObjectHandle>("/vrep/simRosGetObjectHandle");
00327
00328 command_joints_position_pub = n.advertise<vrep_common::JointSetStateData>("/vrep/command_joints_position",1000);
00329
00330 ros::Subscriber notify_joints_position_sub = n.subscribe("/vrep/notify_joints_position", 1000, jointsCallback);
00331
00332
00333
00334
00335
00336 ros::Subscriber notify_sensors_data_sub = n.subscribe("/vrep/notify_sensors_data", 1000, sensorsCallback);
00337
00338 objectHandles();
00339
00340 ros::Rate loop_rate(1000);
00341
00342 while (ros::ok())
00343 {
00344 setJointValue();
00345
00346 ros::spinOnce();
00347 loop_rate.sleep();
00348 }
00349
00350 hdStopScheduler();
00351 hdDisableDevice(hHD);
00352
00353 return 0;
00354 }