MorphGI / Mbed OS MGI_Rebuild_MidLevel_9_0-Basic_PWM

Dependencies:   ros_lib_kinetic

HLComms.cpp

Committer:
WD40andTape
Date:
2019-02-06
Revision:
28:8e0c502c1a50
Parent:
19:e5acb2183d4e
Child:
29:10a5cf37a875

File content as of revision 28:8e0c502c1a50:

// HLComms.cpp

#include "HLComms.h"

HLComms::HLComms(unsigned short int freq_hz) : // Constructor
    newData(1),
    _freq_hz(freq_hz),
    _threadROS(osPriorityBelowNormal),
    _rosReady(1),
    _semSpin(1)
{
    _threadROS.start(callback(this, &HLComms::ros_main));// Start ROS thread
    _rosReady.wait();
}

/*HLComms::~HLComms(void) { // Destructor
    delete *_sensor_pub;
    delete *_duration_pub;
}*/

// ROS

void HLComms::ros_main(void) {
    //printf("HELLO\r\n");
    _nh.getHardware()->setBaud(BAUD_RATE);
    _nh.initNode();
    wait_ms(1000);
    
    ros::Subscriber<std_msgs::Float32MultiArray,HLComms> demands_sub("ML_Demands", &HLComms::receive_demands, this);
    _nh.subscribe(demands_sub);
    
    _sensor_msg.data_length = N_CHANNELS*2;
    _sensor_pub = new ros::Publisher("ML_Sensors", &_sensor_msg);
    _nh.advertise(*_sensor_pub);
    
    _duration_pub = new ros::Publisher("ML_Duration", &_duration_msg);
    _nh.advertise(*_duration_pub);
    
    wait_ms(1000);
    _rosReady.release();
    
    Ticker spinTicker;
    spinTicker.attach(callback(this,&HLComms::releaseSemSpin), 1/(float)_freq_hz); // Set up HL comms to recur at fixed intervals
    
    while (1) {
        _semSpin.wait();
        _nh.spinOnce();
    }
}

void HLComms::releaseSemSpin(void) {
    _semSpin.release();
}

// INPUT

void HLComms::receive_demands(const std_msgs::Float32MultiArray &demands_array) {
    struct demands_struct _protected_input;
    recv_mutex.lock();
    /*for(int i=0; i<N_CHANNELS-1; i++) {
        _protected_input.psi_mm[i] = demands_array.data[i];
    }
    short int demands_array_length = sizeof(demands_array.data)/sizeof(demands_array.data[0]);
    _protected_input.speed_mmps = demands_array.data[demands_array_length-1];*/
    _protected_input.psi_mm[0] = demands_array.data[0];
    _protected_input.psi_mm[1] = demands_array.data[1];
    _protected_input.psi_mm[2] = demands_array.data[2];
    _protected_input.psi_mm[3] = demands_array.data[3];
    _protected_input.psi_mm[4] = demands_array.data[4];
    _protected_input.psi_mm[5] = demands_array.data[5];
    _protected_input.psi_mm[6] = demands_array.data[6];
    _protected_input.psi_mm[7] = demands_array.data[7];
    _protected_input.psi_mm[8] = demands_array.data[8];
    _protected_input.speed_mmps = demands_array.data[9];
    recv_mutex.unlock();
    _input = _protected_input;
    newData.release();
}

demands_struct HLComms::get_demands(void) {
    return _input;
}

// OUTPUT

void HLComms::send_duration_message(double dblTime) {
    _duration_msg.data = dblTime;
    _duration_pub->publish(&_duration_msg);
}

void HLComms::send_sensor_message(double positions[], double pressures[]) {
    short int i_channel;
    for(short int i=0; i<N_CHANNELS*2; i++) {
        i_channel = i%N_CHANNELS;
        if(i<N_CHANNELS) {
            _sensor_msg.data[i] = positions[i_channel];
        } else {
            _sensor_msg.data[i] = pressures[i_channel];
        }
    }
    _sensor_pub->publish(&_sensor_msg);
}