main.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <ros/ros.h>
33 #include <std_msgs/String.h>
34 
35 #include <sstream>
36 #include <unistd.h>
37 #include <iostream>
38 #include <cmath>
39 
40 #include <sys/types.h>
41 #include <unistd.h>
42 #include <stdlib.h>
43 
45 #include <hitec5980sg/hitec5980sg.h>
46 
47 #include <phantom_control/State.h>
48 #include <humanoid_control/Humanoid.h>
49 
50 
51 using namespace ros;
52 using namespace std;
53 
54 
56 
57 phantom_control::State g_PState;
58 humanoid_control::Humanoid g_RState;
59 
60 
62 short int firsttme=1;
63 
64 //const short int id_list[12]={11,12,13,15,16,21,22,23,25,26,31,32};
65 const short int id_list[12]={11,21,12,22,13,23,15,25,16,26,31,32}; // bottom to top servo's command
66 
67 void PhantomCallBk ( const phantom_control::State &phantom_state )
68 {
69  double joint_angle, current_POS;
70  double z_scale = 0.5, x_scale = 5, y_scale=0.8;
71 
72  //cout<<"Pos XX: "<<phantom_state.position[0]<<"\tPos YY: "<<phantom_state.position[1]<<"\tPos ZZ: "<<phantom_state.position[2]<<endl;
73 
74  g_PState=phantom_state;
75 
76  if(g_human->RoboState.op_mode==1)
77  {
78  current_POS=g_PState.position[1];
79 
80  joint_angle = acos ((g_ZZ + current_POS * z_scale)/ g_ZZ) * 180.0 / PI;
81 
82  if(isnan(joint_angle)) joint_angle=0;
83  if(joint_angle>20.) joint_angle=20.0;
84 
85  g_human->RoboState.joint_wanted[2]=joint_angle;
86  g_human->RoboState.joint_wanted[3]=joint_angle;
87  g_human->RoboState.joint_wanted[4]=joint_angle*2.;
88  g_human->RoboState.joint_wanted[5]=joint_angle*2.;
89  g_human->RoboState.joint_wanted[8]=joint_angle;
90  g_human->RoboState.joint_wanted[9]=joint_angle;
91 
92  cout<<"Ankle angle = "<<joint_angle<<endl;
93  }
94  else if(g_human->RoboState.op_mode==2)
95  {
96  current_POS=g_PState.position[0];
97 
98  joint_angle = atan2(current_POS * x_scale, g_ZZ) * 180.0 / PI;
99 
100  if(isnan(joint_angle)) joint_angle=0;
101  if(joint_angle>30.) joint_angle=30.0;
102  if(joint_angle<-30.) joint_angle=-30.0;
103 
104  g_human->RoboState.joint_wanted[0]=-joint_angle;
105  g_human->RoboState.joint_wanted[1]=joint_angle;
106  g_human->RoboState.joint_wanted[6]=joint_angle;
107  g_human->RoboState.joint_wanted[7]=-joint_angle;
108 
109  cout<<"Ankle angle = "<<joint_angle<<endl;
110  }
111  else if(g_human->RoboState.op_mode==3)
112  {
113  if (firsttme==1)
114  {
115  cout<<"First Time"<<endl;
116 
123 
124  firsttme=0;
125  }
126  else
127  {
128  current_POS=-g_PState.position[2];
129 
130  joint_angle = asin((current_POS * y_scale)/THIGH_LENGTH) * 180.0 / PI + 20.;
131 
132  //if(isnan(joint_angle)) joint_angle=0;
133  if(joint_angle>0.) g_human->RoboState.joint_wanted[4]=joint_angle*2.;
134  if(joint_angle<0.) g_human->RoboState.joint_wanted[4]=joint_angle/2.;
135 
138  //g_human->RoboState.joint_wanted[4]=joint_angle*2.;
140  g_human->RoboState.joint_wanted[8]=joint_angle;
141  g_human->RoboState.joint_wanted[9]=joint_angle;
142 
143  cout<<"Hip angle = "<<joint_angle<<endl;
144 
145  }
146  }
147  else if(g_human->RoboState.op_mode==0)
148  {
149 
150 
151 
152  for (int i = 0; i < 13; i++)
153  {
155  }
156  }
157 }
158 
163 int main(int argc, char** argv)
164 {
165  short unsigned int resp=65535;
166 
167  // ROS
168  ros::init( argc, argv, "humanoid_node" );//nome
169 
170  ros::NodeHandle n("~");
171 
172  ros::Publisher pub_state= n.advertise< humanoid_control::Humanoid >( "/humanoid_state", 1000 );
173 
174  ros::Subscriber sub_force = n.subscribe ( "/phantom_state", 1, PhantomCallBk );
175 
176  int op_mode = 0;
177  int op_mode_default = 0;
178  n.param("op_mode", op_mode, op_mode_default );
179 
180  g_human = (ServoHumanoid*) new ServoHumanoid("/dev/ttyUSB0");
181 
182  if(op_mode==0)
183  {
184  ROS_INFO("Operation mode of humanoid robot is 0");
185  ROS_INFO("STOP MODE");
186 
187  g_human->RoboState.op_mode=op_mode;
200 
201  }else if(op_mode==1)
202  {
203  ROS_INFO("Operation mode of humanoid robot is 1");
204  ROS_INFO("BOUNCY MODE");
205  g_human->RoboState.op_mode=op_mode;
206  }else if(op_mode==2)
207  {
208  ROS_INFO("Operation mode of humanoid robot is 2");
209  ROS_INFO("SHAKY MODE");
210  g_human->RoboState.op_mode=op_mode;
211  }else if(op_mode==3)
212  {
213  ROS_INFO("Operation mode of humanoid robot is 3");
214  ROS_INFO("HUMPING MODE");
215  g_human->RoboState.op_mode=op_mode;
216  }
217 
218  for (int i = 0; i < 12; i++)
219  {
221  }
222  //g_human->RoboState.speed_wanted[2]=3*50;
223  //g_human->RoboState.speed_wanted[3]=3*50;
224 
226 
227 
228 // // test loop
229 // short int id;
230 // double pos;
231 // while(1)
232 // {
233 // cout<<"Set servo id:"<<endl;
234 // cin>>id;
235 // if(id==555) exit(0);
236 // cout<<"Set angle to move servo "<<id<<" :"<<endl;
237 // cin>>pos;
238 // resp = g_human->MoveJoint(id, pos);
239 // cout<<"The servo responded "<<resp<<" to the command."<<endl;
240 // }
241 // return 0;
242 // // end test loop
243 
244 
245  g_RState.speed_g_static=g_human->RoboState.speed_g_static;
246 
247  int pid = getpid(), rpid;
248 
249  boost::format fmt("sudo renice -10 %d");
250  fmt % pid;
251 
252  rpid = std::system(fmt.str().c_str());
253 
254  while(ros::ok())
255  {
256  for (uint i = 0; i <12 ; i++)
257  {
259  {
261 
262  //cout<<"Robot needs to change position in joint "<<id_list[i]<<" : position now "<<g_human->RoboState.joint_now[i]<<" position wanted "<<g_human->RoboState.joint_wanted[i]<<endl;
263  }
264 
267  }
268 
269  for (int i = 0; i < 13 ; i++)
270  {
271  g_RState.joint_now[i]=g_human->RoboState.joint_now[i];
272  g_RState.speed_wanted[i]=g_human->RoboState.speed_wanted[i];
273  g_RState.speed_wanted[i]=g_human->RoboState.speed_wanted[i];
274  }
275 
276  g_RState.header.stamp=ros::Time::now();
277  // publish HumanState
278  pub_state.publish( g_RState );
279 
280 
281  ros::spinOnce ( );
282  }
283 
284  delete g_human;
285 
286 
287  return 0;
288 }
short unsigned int SetJointSpeed(short int id, unsigned int speed)
int main(int argc, char **argv)
Definition: main.cpp:163
void HomePosition(void)
double ConvertServoValueByID(int id, short unsigned int servo_value)
short int firsttme
Definition: main.cpp:62
phantom_control::State g_PState
Definition: main.cpp:57
humanoid_control::Humanoid g_RState
Definition: main.cpp:58
#define THIGH_LENGTH
Definition: servohumanoid.h:47
void PhantomCallBk(const phantom_control::State &phantom_state)
Definition: main.cpp:67
ServoHumanoid * g_human
Definition: main.cpp:55
#define PI
Definition: servohumanoid.h:37
#define LEG_LENGTH
Definition: servohumanoid.h:46
short unsigned int MoveJoint(short int id, double joint_angle)
struct ServoHumanoid::RoboState RoboState
const short int id_list[12]
Definition: main.cpp:65
short unsigned int op_mode
Class develop to control PHUA robot's servomotors using hitec_5980SG Lar3's' module.
const double g_ZZ
Definition: main.cpp:61


humanoid_control
Author(s): Emilio Estrelinha, César Sousa
autogenerated on Mon Mar 2 2015 01:31:42