Basic Mid-Level control for the rebuilt MorphGI control unit, using PWM to communicate with the low level controllers.

Dependencies:   ros_lib_kinetic

Committer:
dofydoink
Date:
Thu Jun 24 20:34:47 2021 +0000
Revision:
42:5a5ad23a4bb1
Parent:
37:37da606f4466
first

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