Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: ros_lib_kinetic
HLComms.h
- Committer:
 - WD40andTape
 - Date:
 - 2019-03-06
 - Revision:
 - 31:08cb04eb75fc
 - Parent:
 - 30:6c8eea90735e
 - Child:
 - 33:9877ca32e43c
 
File content as of revision 31:08cb04eb75fc:
// HLComms.h
#ifndef HLCOMMS_H
#define HLCOMMS_H
// STANDARD IMPORTS
#include <algorithm>
// MBED IMPORTS
#include"mbed.h"
#include "mbed_events.h"
// ROS IMPORTS
#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Int16MultiArray.h>
#include <std_msgs/Float32MultiArray.h>
#include "std_msgs/MultiArrayLayout.h"
#include "std_msgs/MultiArrayDimension.h"
// CUSTOM IMPORTS
#include "MLSettings.h"
struct demands_struct {
    double psi_mm[N_CHANNELS];
    double speeds_mmps[3];
};
class HLComms
{
    public:
        
        Semaphore newData;
        
        HLComms(unsigned short int freq_hz);
        //~HLComms(void);
        demands_struct get_demands(void);
        void send_text_message(char text[]);
        void send_durations_message(double dblTimes[]);
        void send_sensor_message(unsigned int positions[], unsigned int pressures[]);
    
    private:
    
        unsigned short int _freq_hz;
        struct demands_struct _input;
        
        Thread _threadROS;
        Semaphore _rosReady;
        Semaphore _semSpin;
        ros::NodeHandle _nh;
        ros::Publisher* _text_pub;
        std_msgs::String _text_msg;
        std_msgs::Int16MultiArray _sensor_msg;
        ros::Publisher* _sensor_pub;
        std_msgs::Float32MultiArray _durations_msg;
        ros::Publisher* _durations_pub;
        Mutex recv_mutex;
        
        void ros_main(void);
        void releaseSemSpin(void);
        //void receive_demands(const std_msgs::Int16MultiArray &demands_array);
        void receive_demands(const std_msgs::Float32MultiArray &demands_array);
};
#endif