MorphGI / Mbed OS LoCoMoTE_MidLevel_7-0

Dependencies:   ros_lib_kinetic

Committer:
WD40andTape
Date:
Wed Mar 06 10:28:59 2019 +0000
Revision:
31:08cb04eb75fc
Parent:
30:6c8eea90735e
Child:
33:9877ca32e43c
Updated to accept input speed, process, and output time separately for each segment. Tested and working.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
WD40andTape 7:5b6a2cefbf3b 1 // HLComms.h
WD40andTape 7:5b6a2cefbf3b 2
WD40andTape 7:5b6a2cefbf3b 3 #ifndef HLCOMMS_H
WD40andTape 7:5b6a2cefbf3b 4 #define HLCOMMS_H
WD40andTape 7:5b6a2cefbf3b 5
WD40andTape 7:5b6a2cefbf3b 6 // STANDARD IMPORTS
WD40andTape 29:10a5cf37a875 7 #include <algorithm>
WD40andTape 7:5b6a2cefbf3b 8 // MBED IMPORTS
WD40andTape 28:8e0c502c1a50 9 #include"mbed.h"
WD40andTape 28:8e0c502c1a50 10 #include "mbed_events.h"
WD40andTape 28:8e0c502c1a50 11 // ROS IMPORTS
WD40andTape 28:8e0c502c1a50 12 #include <ros.h>
WD40andTape 29:10a5cf37a875 13 #include <std_msgs/String.h>
WD40andTape 28:8e0c502c1a50 14 #include <std_msgs/Float32.h>
WD40andTape 29:10a5cf37a875 15 #include <std_msgs/Int16MultiArray.h>
WD40andTape 30:6c8eea90735e 16 #include <std_msgs/Float32MultiArray.h>
WD40andTape 28:8e0c502c1a50 17 #include "std_msgs/MultiArrayLayout.h"
WD40andTape 28:8e0c502c1a50 18 #include "std_msgs/MultiArrayDimension.h"
dofydoink 12:595ed862e52f 19 // CUSTOM IMPORTS
dofydoink 12:595ed862e52f 20 #include "MLSettings.h"
WD40andTape 7:5b6a2cefbf3b 21
WD40andTape 28:8e0c502c1a50 22 struct demands_struct {
WD40andTape 29:10a5cf37a875 23 double psi_mm[N_CHANNELS];
WD40andTape 31:08cb04eb75fc 24 double speeds_mmps[3];
WD40andTape 7:5b6a2cefbf3b 25 };
WD40andTape 7:5b6a2cefbf3b 26
WD40andTape 7:5b6a2cefbf3b 27 class HLComms
WD40andTape 7:5b6a2cefbf3b 28 {
WD40andTape 7:5b6a2cefbf3b 29 public:
WD40andTape 28:8e0c502c1a50 30
WD40andTape 28:8e0c502c1a50 31 Semaphore newData;
WD40andTape 7:5b6a2cefbf3b 32
WD40andTape 28:8e0c502c1a50 33 HLComms(unsigned short int freq_hz);
WD40andTape 28:8e0c502c1a50 34 //~HLComms(void);
WD40andTape 28:8e0c502c1a50 35 demands_struct get_demands(void);
WD40andTape 29:10a5cf37a875 36 void send_text_message(char text[]);
WD40andTape 31:08cb04eb75fc 37 void send_durations_message(double dblTimes[]);
WD40andTape 29:10a5cf37a875 38 void send_sensor_message(unsigned int positions[], unsigned int pressures[]);
WD40andTape 7:5b6a2cefbf3b 39
WD40andTape 7:5b6a2cefbf3b 40 private:
WD40andTape 7:5b6a2cefbf3b 41
WD40andTape 28:8e0c502c1a50 42 unsigned short int _freq_hz;
WD40andTape 28:8e0c502c1a50 43 struct demands_struct _input;
WD40andTape 7:5b6a2cefbf3b 44
WD40andTape 28:8e0c502c1a50 45 Thread _threadROS;
WD40andTape 28:8e0c502c1a50 46 Semaphore _rosReady;
WD40andTape 28:8e0c502c1a50 47 Semaphore _semSpin;
WD40andTape 28:8e0c502c1a50 48 ros::NodeHandle _nh;
WD40andTape 29:10a5cf37a875 49 ros::Publisher* _text_pub;
WD40andTape 29:10a5cf37a875 50 std_msgs::String _text_msg;
WD40andTape 29:10a5cf37a875 51 std_msgs::Int16MultiArray _sensor_msg;
WD40andTape 28:8e0c502c1a50 52 ros::Publisher* _sensor_pub;
WD40andTape 31:08cb04eb75fc 53 std_msgs::Float32MultiArray _durations_msg;
WD40andTape 31:08cb04eb75fc 54 ros::Publisher* _durations_pub;
WD40andTape 28:8e0c502c1a50 55
WD40andTape 17:bbaf3e8440ad 56 Mutex recv_mutex;
WD40andTape 17:bbaf3e8440ad 57
WD40andTape 28:8e0c502c1a50 58 void ros_main(void);
WD40andTape 31:08cb04eb75fc 59 void releaseSemSpin(void);
WD40andTape 30:6c8eea90735e 60 //void receive_demands(const std_msgs::Int16MultiArray &demands_array);
WD40andTape 30:6c8eea90735e 61 void receive_demands(const std_msgs::Float32MultiArray &demands_array);
WD40andTape 7:5b6a2cefbf3b 62
WD40andTape 7:5b6a2cefbf3b 63 };
WD40andTape 7:5b6a2cefbf3b 64
WD40andTape 7:5b6a2cefbf3b 65 #endif