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

Dependencies:   ros_lib_kinetic

Revision:
31:08cb04eb75fc
Parent:
30:6c8eea90735e
Child:
33:9877ca32e43c
--- a/HLComms.h	Fri Feb 15 10:29:23 2019 +0000
+++ b/HLComms.h	Wed Mar 06 10:28:59 2019 +0000
@@ -21,7 +21,7 @@
 
 struct demands_struct {
     double psi_mm[N_CHANNELS];
-    double speed_mmps;
+    double speeds_mmps[3];
 };
 
 class HLComms
@@ -34,7 +34,7 @@
         //~HLComms(void);
         demands_struct get_demands(void);
         void send_text_message(char text[]);
-        void send_duration_message(double dblTime);
+        void send_durations_message(double dblTimes[]);
         void send_sensor_message(unsigned int positions[], unsigned int pressures[]);
     
     private:
@@ -50,13 +50,13 @@
         std_msgs::String _text_msg;
         std_msgs::Int16MultiArray _sensor_msg;
         ros::Publisher* _sensor_pub;
-        std_msgs::Float32 _duration_msg;
-        ros::Publisher* _duration_pub;
+        std_msgs::Float32MultiArray _durations_msg;
+        ros::Publisher* _durations_pub;
 
         Mutex recv_mutex;
         
         void ros_main(void);
-        void HLComms::releaseSemSpin(void);
+        void releaseSemSpin(void);
         //void receive_demands(const std_msgs::Int16MultiArray &demands_array);
         void receive_demands(const std_msgs::Float32MultiArray &demands_array);