Dependencies: ros_lib_kinetic
HLComms.cpp@30:6c8eea90735e, 2019-02-15 (annotated)
- Committer:
- WD40andTape
- Date:
- Fri Feb 15 10:29:23 2019 +0000
- Revision:
- 30:6c8eea90735e
- Parent:
- 29:10a5cf37a875
- Child:
- 31:08cb04eb75fc
Serial communication now tested, smooth and stable.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
WD40andTape | 7:5b6a2cefbf3b | 1 | // HLComms.cpp |
WD40andTape | 7:5b6a2cefbf3b | 2 | |
WD40andTape | 7:5b6a2cefbf3b | 3 | #include "HLComms.h" |
WD40andTape | 7:5b6a2cefbf3b | 4 | |
WD40andTape | 28:8e0c502c1a50 | 5 | HLComms::HLComms(unsigned short int freq_hz) : // Constructor |
WD40andTape | 28:8e0c502c1a50 | 6 | newData(1), |
WD40andTape | 28:8e0c502c1a50 | 7 | _freq_hz(freq_hz), |
WD40andTape | 28:8e0c502c1a50 | 8 | _threadROS(osPriorityBelowNormal), |
WD40andTape | 28:8e0c502c1a50 | 9 | _rosReady(1), |
WD40andTape | 28:8e0c502c1a50 | 10 | _semSpin(1) |
WD40andTape | 28:8e0c502c1a50 | 11 | { |
WD40andTape | 28:8e0c502c1a50 | 12 | _threadROS.start(callback(this, &HLComms::ros_main));// Start ROS thread |
WD40andTape | 28:8e0c502c1a50 | 13 | _rosReady.wait(); |
WD40andTape | 7:5b6a2cefbf3b | 14 | } |
WD40andTape | 7:5b6a2cefbf3b | 15 | |
WD40andTape | 28:8e0c502c1a50 | 16 | /*HLComms::~HLComms(void) { // Destructor |
WD40andTape | 29:10a5cf37a875 | 17 | delete *_text_pub; |
WD40andTape | 28:8e0c502c1a50 | 18 | delete *_sensor_pub; |
WD40andTape | 28:8e0c502c1a50 | 19 | delete *_duration_pub; |
WD40andTape | 28:8e0c502c1a50 | 20 | }*/ |
WD40andTape | 28:8e0c502c1a50 | 21 | |
WD40andTape | 28:8e0c502c1a50 | 22 | // ROS |
WD40andTape | 28:8e0c502c1a50 | 23 | |
WD40andTape | 28:8e0c502c1a50 | 24 | void HLComms::ros_main(void) { |
WD40andTape | 28:8e0c502c1a50 | 25 | _nh.getHardware()->setBaud(BAUD_RATE); |
WD40andTape | 28:8e0c502c1a50 | 26 | _nh.initNode(); |
WD40andTape | 28:8e0c502c1a50 | 27 | wait_ms(1000); |
WD40andTape | 28:8e0c502c1a50 | 28 | |
WD40andTape | 30:6c8eea90735e | 29 | //ros::Subscriber<std_msgs::Int16MultiArray,HLComms> demands_sub("ML_Demands", &HLComms::receive_demands, this); |
WD40andTape | 30:6c8eea90735e | 30 | ros::Subscriber<std_msgs::Float32MultiArray,HLComms> demands_sub("ML_Demands", &HLComms::receive_demands, this); |
WD40andTape | 28:8e0c502c1a50 | 31 | _nh.subscribe(demands_sub); |
WD40andTape | 28:8e0c502c1a50 | 32 | |
WD40andTape | 29:10a5cf37a875 | 33 | _text_pub = new ros::Publisher("ML_TextOut", &_text_msg); |
WD40andTape | 29:10a5cf37a875 | 34 | _nh.advertise(*_text_pub); |
WD40andTape | 29:10a5cf37a875 | 35 | |
WD40andTape | 28:8e0c502c1a50 | 36 | _sensor_msg.data_length = N_CHANNELS*2; |
WD40andTape | 28:8e0c502c1a50 | 37 | _sensor_pub = new ros::Publisher("ML_Sensors", &_sensor_msg); |
WD40andTape | 28:8e0c502c1a50 | 38 | _nh.advertise(*_sensor_pub); |
WD40andTape | 28:8e0c502c1a50 | 39 | |
WD40andTape | 28:8e0c502c1a50 | 40 | _duration_pub = new ros::Publisher("ML_Duration", &_duration_msg); |
WD40andTape | 28:8e0c502c1a50 | 41 | _nh.advertise(*_duration_pub); |
WD40andTape | 28:8e0c502c1a50 | 42 | |
WD40andTape | 28:8e0c502c1a50 | 43 | wait_ms(1000); |
WD40andTape | 28:8e0c502c1a50 | 44 | _rosReady.release(); |
WD40andTape | 28:8e0c502c1a50 | 45 | |
WD40andTape | 28:8e0c502c1a50 | 46 | Ticker spinTicker; |
WD40andTape | 28:8e0c502c1a50 | 47 | spinTicker.attach(callback(this,&HLComms::releaseSemSpin), 1/(float)_freq_hz); // Set up HL comms to recur at fixed intervals |
WD40andTape | 28:8e0c502c1a50 | 48 | |
WD40andTape | 28:8e0c502c1a50 | 49 | while (1) { |
WD40andTape | 28:8e0c502c1a50 | 50 | _semSpin.wait(); |
WD40andTape | 28:8e0c502c1a50 | 51 | _nh.spinOnce(); |
WD40andTape | 7:5b6a2cefbf3b | 52 | } |
WD40andTape | 7:5b6a2cefbf3b | 53 | } |
WD40andTape | 7:5b6a2cefbf3b | 54 | |
WD40andTape | 28:8e0c502c1a50 | 55 | void HLComms::releaseSemSpin(void) { |
WD40andTape | 28:8e0c502c1a50 | 56 | _semSpin.release(); |
WD40andTape | 9:cd3607ba5643 | 57 | } |
WD40andTape | 9:cd3607ba5643 | 58 | |
WD40andTape | 28:8e0c502c1a50 | 59 | // INPUT |
WD40andTape | 9:cd3607ba5643 | 60 | |
WD40andTape | 30:6c8eea90735e | 61 | /*void HLComms::receive_demands(const std_msgs::Int16MultiArray &demands_array) { |
WD40andTape | 28:8e0c502c1a50 | 62 | struct demands_struct _protected_input; |
WD40andTape | 28:8e0c502c1a50 | 63 | recv_mutex.lock(); |
WD40andTape | 29:10a5cf37a875 | 64 | for(int i=0; i<N_CHANNELS; i++) { |
WD40andTape | 30:6c8eea90735e | 65 | _protected_input.psi_mm[i] = ((MAX_ACTUATOR_LIMIT_MM+1.0)*((double)demands_array.data[i]/65535)-1.0); |
WD40andTape | 30:6c8eea90735e | 66 | if( _protected_input.psi_mm[i]<-0.5 ) { |
WD40andTape | 30:6c8eea90735e | 67 | _protected_input.psi_mm[i] = -1.0; |
WD40andTape | 30:6c8eea90735e | 68 | } else { |
WD40andTape | 30:6c8eea90735e | 69 | _protected_input.psi_mm[i] = min( max(_protected_input.psi_mm[i],0.0) , (double)MAX_ACTUATOR_LIMIT_MM ); |
WD40andTape | 30:6c8eea90735e | 70 | } |
WD40andTape | 7:5b6a2cefbf3b | 71 | } |
WD40andTape | 29:10a5cf37a875 | 72 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! |
WD40andTape | 29:10a5cf37a875 | 73 | //short int demands_array_length = sizeof(demands_array.data)/sizeof(demands_array.data[0]); |
WD40andTape | 29:10a5cf37a875 | 74 | //_protected_input.speed_mmps = demands_array.data[demands_array_length-1]; |
WD40andTape | 30:6c8eea90735e | 75 | _protected_input.speed_mmps = MAX_SPEED_MMPS*((double)demands_array.data[9]/65535); |
WD40andTape | 29:10a5cf37a875 | 76 | _protected_input.speed_mmps = min( max(_protected_input.speed_mmps,0.0) , (double)MAX_SPEED_MMPS ); |
WD40andTape | 28:8e0c502c1a50 | 77 | recv_mutex.unlock(); |
WD40andTape | 28:8e0c502c1a50 | 78 | _input = _protected_input; |
WD40andTape | 30:6c8eea90735e | 79 | //char array[20]; |
WD40andTape | 30:6c8eea90735e | 80 | //sprintf(array, "Speed: %f", _input.speed_mmps); |
WD40andTape | 30:6c8eea90735e | 81 | //send_text_message(array); |
WD40andTape | 30:6c8eea90735e | 82 | newData.release(); |
WD40andTape | 30:6c8eea90735e | 83 | }*/ |
WD40andTape | 30:6c8eea90735e | 84 | |
WD40andTape | 30:6c8eea90735e | 85 | void HLComms::receive_demands(const std_msgs::Float32MultiArray &demands_array) { |
WD40andTape | 30:6c8eea90735e | 86 | struct demands_struct _protected_input; |
WD40andTape | 30:6c8eea90735e | 87 | recv_mutex.lock(); |
WD40andTape | 30:6c8eea90735e | 88 | for(int i=0; i<N_CHANNELS; i++) { |
WD40andTape | 30:6c8eea90735e | 89 | _protected_input.psi_mm[i] = (double)demands_array.data[i]; |
WD40andTape | 30:6c8eea90735e | 90 | if( _protected_input.psi_mm[i]<-0.5 ) { |
WD40andTape | 30:6c8eea90735e | 91 | _protected_input.psi_mm[i] = -1.0; |
WD40andTape | 30:6c8eea90735e | 92 | } else { |
WD40andTape | 30:6c8eea90735e | 93 | _protected_input.psi_mm[i] = min( max(_protected_input.psi_mm[i],0.0) , (double)MAX_ACTUATOR_LIMIT_MM ); |
WD40andTape | 30:6c8eea90735e | 94 | } |
WD40andTape | 30:6c8eea90735e | 95 | } |
WD40andTape | 30:6c8eea90735e | 96 | _protected_input.speed_mmps = (double)demands_array.data[9]; |
WD40andTape | 30:6c8eea90735e | 97 | _protected_input.speed_mmps = min( max(_protected_input.speed_mmps,0.0) , (double)MAX_SPEED_MMPS ); |
WD40andTape | 30:6c8eea90735e | 98 | recv_mutex.unlock(); |
WD40andTape | 30:6c8eea90735e | 99 | _input = _protected_input; |
WD40andTape | 28:8e0c502c1a50 | 100 | newData.release(); |
WD40andTape | 17:bbaf3e8440ad | 101 | } |
WD40andTape | 17:bbaf3e8440ad | 102 | |
WD40andTape | 28:8e0c502c1a50 | 103 | demands_struct HLComms::get_demands(void) { |
WD40andTape | 28:8e0c502c1a50 | 104 | return _input; |
WD40andTape | 28:8e0c502c1a50 | 105 | } |
WD40andTape | 28:8e0c502c1a50 | 106 | |
WD40andTape | 28:8e0c502c1a50 | 107 | // OUTPUT |
WD40andTape | 28:8e0c502c1a50 | 108 | |
WD40andTape | 29:10a5cf37a875 | 109 | void HLComms::send_text_message(char text[]) { |
WD40andTape | 29:10a5cf37a875 | 110 | _text_msg.data = text; |
WD40andTape | 29:10a5cf37a875 | 111 | _text_pub->publish(&_text_msg); |
WD40andTape | 29:10a5cf37a875 | 112 | } |
WD40andTape | 29:10a5cf37a875 | 113 | |
WD40andTape | 28:8e0c502c1a50 | 114 | void HLComms::send_duration_message(double dblTime) { |
WD40andTape | 28:8e0c502c1a50 | 115 | _duration_msg.data = dblTime; |
WD40andTape | 28:8e0c502c1a50 | 116 | _duration_pub->publish(&_duration_msg); |
WD40andTape | 9:cd3607ba5643 | 117 | } |
WD40andTape | 9:cd3607ba5643 | 118 | |
WD40andTape | 29:10a5cf37a875 | 119 | void HLComms::send_sensor_message(unsigned int positions[], unsigned int pressures[]) { |
WD40andTape | 28:8e0c502c1a50 | 120 | short int i_channel; |
WD40andTape | 28:8e0c502c1a50 | 121 | for(short int i=0; i<N_CHANNELS*2; i++) { |
WD40andTape | 28:8e0c502c1a50 | 122 | i_channel = i%N_CHANNELS; |
WD40andTape | 28:8e0c502c1a50 | 123 | if(i<N_CHANNELS) { |
WD40andTape | 28:8e0c502c1a50 | 124 | _sensor_msg.data[i] = positions[i_channel]; |
WD40andTape | 28:8e0c502c1a50 | 125 | } else { |
WD40andTape | 28:8e0c502c1a50 | 126 | _sensor_msg.data[i] = pressures[i_channel]; |
WD40andTape | 28:8e0c502c1a50 | 127 | } |
WD40andTape | 28:8e0c502c1a50 | 128 | } |
WD40andTape | 28:8e0c502c1a50 | 129 | _sensor_pub->publish(&_sensor_msg); |
WD40andTape | 9:cd3607ba5643 | 130 | } |