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
00032 #include <ros/ros.h>
00033 #include <std_msgs/String.h>
00034
00035 #include <sstream>
00036 #include <unistd.h>
00037 #include <iostream>
00038 #include <cmath>
00039
00040 #include <sys/types.h>
00041 #include <unistd.h>
00042 #include <stdlib.h>
00043
00044 #include <humanoid_control/servohumanoid.h>
00045 #include <hitec5980sg/hitec5980sg.h>
00046
00047 #include <phantom_control/State.h>
00048 #include <humanoid_control/Humanoid.h>
00049
00050
00051 using namespace ros;
00052 using namespace std;
00053
00054
00055 ServoHumanoid *g_human;
00056
00057 phantom_control::State g_PState;
00058 humanoid_control::Humanoid g_RState;
00059
00060
00061 const double g_ZZ=THIGH_LENGTH+LEG_LENGTH;
00062 short int firsttme=1;
00063
00064
00065 const short int id_list[12]={11,21,12,22,13,23,15,25,16,26,31,32};
00066
00067 void PhantomCallBk ( const phantom_control::State &phantom_state )
00068 {
00069 double joint_angle, current_POS;
00070 double z_scale = 0.5, x_scale = 5, y_scale=0.8;
00071
00072
00073
00074 g_PState=phantom_state;
00075
00076 if(g_human->RoboState.op_mode==1)
00077 {
00078 current_POS=g_PState.position[1];
00079
00080 joint_angle = acos ((g_ZZ + current_POS * z_scale)/ g_ZZ) * 180.0 / PI;
00081
00082 if(isnan(joint_angle)) joint_angle=0;
00083 if(joint_angle>20.) joint_angle=20.0;
00084
00085 g_human->RoboState.joint_wanted[2]=joint_angle;
00086 g_human->RoboState.joint_wanted[3]=joint_angle;
00087 g_human->RoboState.joint_wanted[4]=joint_angle*2.;
00088 g_human->RoboState.joint_wanted[5]=joint_angle*2.;
00089 g_human->RoboState.joint_wanted[8]=joint_angle;
00090 g_human->RoboState.joint_wanted[9]=joint_angle;
00091
00092 cout<<"Ankle angle = "<<joint_angle<<endl;
00093 }
00094 else if(g_human->RoboState.op_mode==2)
00095 {
00096 current_POS=g_PState.position[0];
00097
00098 joint_angle = atan2(current_POS * x_scale, g_ZZ) * 180.0 / PI;
00099
00100 if(isnan(joint_angle)) joint_angle=0;
00101 if(joint_angle>30.) joint_angle=30.0;
00102 if(joint_angle<-30.) joint_angle=-30.0;
00103
00104 g_human->RoboState.joint_wanted[0]=-joint_angle;
00105 g_human->RoboState.joint_wanted[1]=joint_angle;
00106 g_human->RoboState.joint_wanted[6]=joint_angle;
00107 g_human->RoboState.joint_wanted[7]=-joint_angle;
00108
00109 cout<<"Ankle angle = "<<joint_angle<<endl;
00110 }
00111 else if(g_human->RoboState.op_mode==3)
00112 {
00113 if (firsttme==1)
00114 {
00115 cout<<"First Time"<<endl;
00116
00117 g_human->RoboState.joint_wanted[2]=20.;
00118 g_human->RoboState.joint_wanted[3]=20.;
00119 g_human->RoboState.joint_wanted[4]=40.;
00120 g_human->RoboState.joint_wanted[5]=40.;
00121 g_human->RoboState.joint_wanted[8]=20.;
00122 g_human->RoboState.joint_wanted[9]=20.;
00123
00124 firsttme=0;
00125 }
00126 else
00127 {
00128 current_POS=-g_PState.position[2];
00129
00130 joint_angle = asin((current_POS * y_scale)/THIGH_LENGTH) * 180.0 / PI + 20.;
00131
00132
00133 if(joint_angle>0.) g_human->RoboState.joint_wanted[4]=joint_angle*2.;
00134 if(joint_angle<0.) g_human->RoboState.joint_wanted[4]=joint_angle/2.;
00135
00136 g_human->RoboState.joint_wanted[2]=20.;
00137 g_human->RoboState.joint_wanted[3]=20.;
00138
00139 g_human->RoboState.joint_wanted[5]=g_human->RoboState.joint_wanted[4];
00140 g_human->RoboState.joint_wanted[8]=joint_angle;
00141 g_human->RoboState.joint_wanted[9]=joint_angle;
00142
00143 cout<<"Hip angle = "<<joint_angle<<endl;
00144
00145 }
00146 }
00147 else if(g_human->RoboState.op_mode==0)
00148 {
00149
00150
00151
00152 for (int i = 0; i < 13; i++)
00153 {
00154 g_human->RoboState.joint_wanted[i]=0;
00155 }
00156 }
00157 }
00158
00163 int main(int argc, char** argv)
00164 {
00165 short unsigned int resp=65535;
00166
00167
00168 ros::init( argc, argv, "humanoid_node" );
00169
00170 ros::NodeHandle n("~");
00171
00172 ros::Publisher pub_state= n.advertise< humanoid_control::Humanoid >( "/humanoid_state", 1000 );
00173
00174 ros::Subscriber sub_force = n.subscribe ( "/phantom_state", 1, PhantomCallBk );
00175
00176 int op_mode = 0;
00177 int op_mode_default = 0;
00178 n.param("op_mode", op_mode, op_mode_default );
00179
00180 g_human = (ServoHumanoid*) new ServoHumanoid("/dev/ttyUSB0");
00181
00182 if(op_mode==0)
00183 {
00184 ROS_INFO("Operation mode of humanoid robot is 0");
00185 ROS_INFO("STOP MODE");
00186
00187 g_human->RoboState.op_mode=op_mode;
00188 g_human->RoboState.joint_wanted[0]=0.;
00189 g_human->RoboState.joint_wanted[1]=0.;
00190 g_human->RoboState.joint_wanted[2]=10.;
00191 g_human->RoboState.joint_wanted[3]=10.;
00192 g_human->RoboState.joint_wanted[4]=20.;
00193 g_human->RoboState.joint_wanted[5]=20.;
00194 g_human->RoboState.joint_wanted[6]=0.;
00195 g_human->RoboState.joint_wanted[7]=0.;
00196 g_human->RoboState.joint_wanted[8]=15.;
00197 g_human->RoboState.joint_wanted[9]=15.;
00198 g_human->RoboState.joint_wanted[10]=0.;
00199 g_human->RoboState.joint_wanted[11]=0.;
00200
00201 }else if(op_mode==1)
00202 {
00203 ROS_INFO("Operation mode of humanoid robot is 1");
00204 ROS_INFO("BOUNCY MODE");
00205 g_human->RoboState.op_mode=op_mode;
00206 }else if(op_mode==2)
00207 {
00208 ROS_INFO("Operation mode of humanoid robot is 2");
00209 ROS_INFO("SHAKY MODE");
00210 g_human->RoboState.op_mode=op_mode;
00211 }else if(op_mode==3)
00212 {
00213 ROS_INFO("Operation mode of humanoid robot is 3");
00214 ROS_INFO("HUMPING MODE");
00215 g_human->RoboState.op_mode=op_mode;
00216 }
00217
00218 for (int i = 0; i < 12; i++)
00219 {
00220 g_human->RoboState.speed_wanted[i]=50;
00221 }
00222
00223
00224
00225 g_human->HomePosition();
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245 g_RState.speed_g_static=g_human->RoboState.speed_g_static;
00246
00247
00248
00249
00250
00251
00252
00253
00254 while(ros::ok())
00255 {
00256 for (uint i = 0; i <12 ; i++)
00257 {
00258 if( (g_human->RoboState.joint_now[i] > (g_human->RoboState.joint_wanted[i] + 1 )) || (g_human->RoboState.joint_now[i] < (g_human->RoboState.joint_wanted[i] - 1 )))
00259 {
00260 resp = g_human->MoveJoint(id_list[i], g_human->RoboState.joint_wanted[i]);
00261
00262
00263 }
00264
00265 resp = g_human->SetJointSpeed(id_list[i], g_human->RoboState.speed_wanted[i]);
00266 g_human->RoboState.joint_now[i]=g_human->ConvertServoValueByID(id_list[i], resp);
00267 }
00268
00269 for (int i = 0; i < 13 ; i++)
00270 {
00271 g_RState.joint_now[i]=g_human->RoboState.joint_now[i];
00272 g_RState.speed_wanted[i]=g_human->RoboState.speed_wanted[i];
00273 g_RState.speed_wanted[i]=g_human->RoboState.speed_wanted[i];
00274 }
00275
00276 g_RState.header.stamp=ros::Time::now();
00277
00278 pub_state.publish( g_RState );
00279
00280
00281 ros::spinOnce ( );
00282 }
00283
00284 delete g_human;
00285
00286
00287 return 0;
00288 }