Dependencies: ros_lib_kinetic
Diff: HLComms.h
- Revision:
- 29:10a5cf37a875
- Parent:
- 28:8e0c502c1a50
- Child:
- 30:6c8eea90735e
--- a/HLComms.h Wed Feb 06 16:10:18 2019 +0000 +++ b/HLComms.h Fri Feb 08 18:36:15 2019 +0000 @@ -4,21 +4,22 @@ #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/Float32MultiArray.h> +#include <std_msgs/Int16MultiArray.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 psi_mm[9]; + double psi_mm[N_CHANNELS]; double speed_mmps; }; @@ -31,8 +32,9 @@ HLComms(unsigned short int freq_hz); //~HLComms(void); demands_struct get_demands(void); + void send_text_message(char text[]); void send_duration_message(double dblTime); - void send_sensor_message(double positions[], double pressures[]); + void send_sensor_message(unsigned int positions[], unsigned int pressures[]); private: @@ -43,8 +45,9 @@ Semaphore _rosReady; Semaphore _semSpin; ros::NodeHandle _nh; - //ros::Subscriber<std_msgs::Float32MultiArray>* _demands_sub; - std_msgs::Float32MultiArray _sensor_msg; + ros::Publisher* _text_pub; + std_msgs::String _text_msg; + std_msgs::Int16MultiArray _sensor_msg; ros::Publisher* _sensor_pub; std_msgs::Float32 _duration_msg; ros::Publisher* _duration_pub; @@ -53,7 +56,7 @@ void ros_main(void); void HLComms::releaseSemSpin(void); - void receive_demands(const std_msgs::Float32MultiArray &demands_array); + void receive_demands(const std_msgs::Int16MultiArray &demands_array); };