射出(3/29用)

Dependencies:   mbed ros_lib_kinetic

Fork of NHK_kaida_ros0322_4 by ROBOSTEP4期

Files at this revision

API Documentation at this revision

Comitter:
Arare
Date:
Mon Apr 09 14:48:36 2018 +0000
Parent:
22:37a07f844778
Commit message:
se

Changed in this revision

main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/main.cpp	Thu Apr 05 07:52:54 2018 +0000
+++ b/main.cpp	Mon Apr 09 14:48:36 2018 +0000
@@ -34,7 +34,8 @@
 int32_t act=101;
 int ball_judgement=1;
 int finding=0;
- 
+int re_lease=0;
+
 Ticker MC;
 std_msgs::Int32 pub_act;
 std_msgs::Int32 pub_b;
@@ -48,6 +49,7 @@
 ros::Publisher pub_color2("act_color2", &pub_c2);
 ros::Publisher pub_finc("shoot_fin", &pub_fin);
 
+
 void messageCallback(const std_msgs::Int32 &msg)
 {
     if(act!=9&&msg.data==9){
@@ -67,6 +69,12 @@
     finding=msg.data;
 }
 
+void messageCallback4(const std_msgs::Int32 &msg)
+{
+    re_lease=msg.data;
+    if(re_lease==1)led1=1;
+}
+
 void MCL()
 {
     pub_b.data=ball_judgement;
@@ -81,7 +89,8 @@
 ros::Subscriber<std_msgs::Int32> sub("shoot_action",&messageCallback);
 ros::Subscriber<std_msgs::Int32> sub_TZ("tz",&messageCallback2);
 ros::Subscriber<std_msgs::Int32> sub_find("find",&messageCallback3);
- 
+ros::Subscriber<std_msgs::Int32> sub_release("release",&messageCallback4);
+
 /////射出サイクル/////
 void throw_cock(float waittime)
 {   
@@ -190,6 +199,7 @@
     nh.subscribe(sub);
     nh.subscribe(sub_TZ);
     nh.subscribe(sub_find);
+    nh.subscribe(sub_release);
     nh.advertise(pub_action);
     nh.advertise(pub_ball);
     nh.advertise(pub_color1);
@@ -218,10 +228,10 @@
         led4=1;
     }    
      else{
-         led1=0;
-         led2=0;
-         led3=0;
-         led4=0;
+         //led1=0;
+         //led2=0;
+         //led3=0;
+         //led4=0;
          }   
     ///装填///
         if(((act==1)||(act==3)||(act==5)||(act==10)||(act==11))&&(ready_action==0)) { //TZ3