action gobeur

Dependencies:   ros_messages mbed Servo Manche_a_air Gobeur ros_lib_melodic

main.cpp

Committer:
kyxstark
Date:
2021-07-08
Revision:
9:59a9831f067d
Parent:
6:4af07c2de6ba
Child:
11:9038da3b84da

File content as of revision 9:59a9831f067d:

/*
 * rosserial Publisher Example
 * Prints "hello world!"
 */

#include"mbed.h"
#include <ros.h>
#include <std_msgs/String.h>
#include <Gobeur.h>
#include <Manche_a_air.h>
#include <Servo.h>
#include <ros_messages/game_manager/GameStatus.h>
#include "actuators.h"
 
Gobeur* gobeurs[2];
Manche_a_air* maas[3]; 

int game_started_f = 0;
 
 
void gobeur_trait_msg(const gobeur_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)
{
    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);
}

 
 
ros::NodeHandle  nh;

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<game_manager_node::game_status_msg> sub_game_status  ("ai/game_manager/status", &on_game_status)  ;

char hello[13] = "hello!";


float clock_s() { return us_ticker_read() / 1000000.0f; }
uint64_t clock_ms() { return us_ticker_read() / 1000; }
uint64_t clock_us() { return us_ticker_read(); }


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[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[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);
    
    nh.initNode();
    nh.advertise(chatter);
    nh.subscribe(sub_gobeur);
    nh.subscribe(sub_maa);
    nh.subscribe(sub_game_status);
    
    str_msg.data = hello;
    chatter.publish( &str_msg );
        
    while (1) {
        gobeurs[0]->automate();
        gobeurs[1]->automate();
        maas[0]->automate();
        maas[1]->automate();
        maas[2]->automate();
        nh.spinOnce();
        
    }
}