
射出(3/29用)
Dependencies: mbed ros_lib_kinetic
Fork of NHK_kaida_ros0322_4 by
Diff: main.cpp
- Revision:
- 17:df95c0fb7b87
- Parent:
- 16:85746e242e49
- Child:
- 18:0184238dccc3
--- a/main.cpp Wed Mar 21 15:55:23 2018 +0000 +++ b/main.cpp Thu Mar 22 06:11:35 2018 +0000 @@ -60,6 +60,10 @@ void messageCallback(const std_msgs::Int32 &msg) { + if(act!=9&&msg.data==9){ + ready_action=1; + count=0; + } act=msg.data; } @@ -135,6 +139,18 @@ } else if (act==7) { fuck=1; + s_grab2=0; + wait(2); + ledw=1; + wait(1); + snap2=0; + wait(waittime); + grab2=0; + wait(1); + ledw=0; + } + else if (act==8) { + fuck=1; s_grab=0; wait(2); ledw=1; @@ -145,27 +161,15 @@ wait(1); ledw=0; } - else if (act==8) { + else if (act==9) { fuck=1; - s_grab2=0; + s_grab=0; wait(2); ledw=1; wait(1); - snap2=0; + snap=0; wait(waittime); - grab2=0; - wait(1); - ledw=0; - } - else if (act==9) { - fuck=1; - s_grab2=0; - wait(2); - ledw=1; - wait(1); - snap2=0; - wait(waittime); - grab2=0; + grab=0; wait(1); ledw=0; } @@ -205,7 +209,6 @@ pub_act.data=0; pub_fin.data=0; pub_b.data=0; - int first_up=0; char cmd[2]; char cell[1]= {0x03}; char data[8]= {0,0,0,0,0,0,0,0}; @@ -336,11 +339,10 @@ ///射出/// if((act==2)&&(count==0)) { int f_i=0; - throw_cock(0.218); //TZ1 + throw_cock(0.243); //TZ1 ready_action=0; count=1; - first_up=0; pub_act.data=act; pub_action.publish(&pub_act); for(f_i=0;f_i<20;f_i++){ @@ -352,11 +354,10 @@ if(((act==4)||(act==6))&&(count==0)) { int f_i=0; - throw_cock(0.218); //TZ2 + throw_cock(0.243); //TZ2 ready_action=0; count=1; - first_up=0; pub_act.data=act; pub_action.publish(&pub_act); for(f_i=0;f_i<20;f_i++){ @@ -368,11 +369,10 @@ if(((act==7)||(act==8)||(act==9))&&(count==0)) { int f_i=0; - throw_cock(0.172); //TZ3 + throw_cock(0.228); //TZ3 ready_action=0; count=1; - first_up=0; pub_act.data=act; pub_action.publish(&pub_act); for(f_i=0;f_i<20;f_i++){