action gobeur

Dependencies:   ros_messages mbed Servo Manche_a_air Gobeur ros_lib_melodic

Revision:
11:9038da3b84da
Parent:
9:59a9831f067d
--- a/main.cpp	Thu Jul 08 17:16:00 2021 +0000
+++ b/main.cpp	Thu Jul 08 22:48:21 2021 +0000
@@ -18,18 +18,28 @@
 int game_started_f = 0;
  
  
-void gobeur_trait_msg(const gobeur_node::Gobeur_msg& gobeur_msg)
+void gobeur_trait_msg(const stm32_actuators_node::Gobeur_msg& gobeur_msg)
 {
     gobeurs[gobeur_msg.index_gobeur]->update_order(gobeur_msg.gobeur_order) ; 
 }
-void maa_trait_msg(const manche_a_air_node::Manche_a_air_msg& maa_msg)
+void maa_trait_msg(const stm32_actuators_node::Manche_a_air_msg& maa_msg)
 {
     maas[maa_msg.index_manche_a_air]->update_order(maa_msg.manche_a_air_order) ; 
 }
 void on_game_status(const game_manager_node::game_status_msg& game_status)
 {
-    game_started_f = 1;
-    maas[2]->set_auto_open(1, 97);
+    if(game_started_f != 1 && game_status.game_status == 1)
+    {
+        game_started_f = 1;
+        maas[2]->set_auto_open(1, 95);
+    }
+    else if(game_status.game_status == 0)
+    {
+    }
+    else if(game_status.game_status == 2)
+    {
+    }
+    
 }
 
  
@@ -39,8 +49,8 @@
 std_msgs::String str_msg;
 ros::Publisher chatter("chatter", &str_msg);
 
-ros::Subscriber<gobeur_node::Gobeur_msg> sub_gobeur("gobeur", &gobeur_trait_msg);
-ros::Subscriber<manche_a_air_node::Manche_a_air_msg> sub_maa("manche_a_air", &maa_trait_msg);
+ros::Subscriber<stm32_actuators_node::Gobeur_msg> sub_gobeur("gobeur", &gobeur_trait_msg);
+ros::Subscriber<stm32_actuators_node::Manche_a_air_msg> sub_maa("manche_a_air", &maa_trait_msg);
 
 
 ros::Subscriber<game_manager_node::game_status_msg> sub_game_status  ("ai/game_manager/status", &on_game_status)  ;
@@ -54,19 +64,19 @@
 
 
 int main() {
-    gobeurs[0] = new Gobeur(GOBEUR_TURBINE_LEFT_PIN, GOBEUR_SERVO_LEFT_PIN, GOBEUR_TURBINE_TH_ON, GOBEUR_TURBINE_TH_OFF, GOBEUR_SERVO_POS_OPEN, GOBEUR_SERVO_POS_CLOSE );
+    gobeurs[0] = new Gobeur(GOBEUR_TURBINE_LEFT_PIN, GOBEUR_SERVO_LEFT_PIN, GOBEUR_TURBINE_TH_ON, GOBEUR_TURBINE_TH_OFF, GOBEUR_SERVO_POS_CLOSE, GOBEUR_SERVO_POS_OPEN );
     gobeurs[1] = new Gobeur(GOBEUR_TURBINE_RIGHT_PIN, GOBEUR_SERVO_RIGHT_PIN, GOBEUR_TURBINE_TH_ON, GOBEUR_TURBINE_TH_OFF, GOBEUR_SERVO_POS_OPEN, GOBEUR_SERVO_POS_CLOSE );
-    maas[0] = new Manche_a_air(MAA_SERVO_LEFT_PIN, MAA_SERVO_POS_OPEN, MAA_SERVO_POS_CLOSE);
+    maas[0] = new Manche_a_air(MAA_SERVO_LEFT_PIN, MAA_SERVO_POS_CLOSE, MAA_SERVO_POS_OPEN);
     maas[1] = new Manche_a_air(MAA_SERVO_RIGHT_PIN, MAA_SERVO_POS_OPEN, MAA_SERVO_POS_CLOSE);
     maas[2] = new Manche_a_air(FLAG_SERVO_PIN, FLAG_SERVO_POS_OPEN, FLAG_SERVO_POS_CLOSE);
     
     //maas[2] = new Manche_a_air(FLAG_SERVO_PIN, FLAG_SERVO_POS_OPEN, FLAG_SERVO_POS_CLOSE);
-    maas[2]->set_auto_open(1, 1);
-    maas[2]->set_auto_close(1, 5);
-    maas[0]->set_auto_open(1, 2);
-    maas[0]->set_auto_close(1, 4);
-    maas[1]->set_auto_open(1, 3);
-    maas[1]->set_auto_close(1, 3);
+    //maas[2]->set_auto_open(1, 1);
+    //maas[2]->set_auto_close(1, 5);
+    //maas[0]->set_auto_open(1, 2);
+    //maas[0]->set_auto_close(1, 4);
+    //maas[1]->set_auto_open(1, 3);
+    //maas[1]->set_auto_close(1, 3);
     
     nh.initNode();
     nh.advertise(chatter);