Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: ros_lib_kinetic
HLComms.cpp
- Committer:
- WD40andTape
- Date:
- 2019-02-08
- Revision:
- 29:10a5cf37a875
- Parent:
- 28:8e0c502c1a50
- Child:
- 30:6c8eea90735e
File content as of revision 29:10a5cf37a875:
// HLComms.cpp
#include "HLComms.h"
HLComms::HLComms(unsigned short int freq_hz) : // Constructor
newData(1),
_freq_hz(freq_hz),
_threadROS(osPriorityBelowNormal),
_rosReady(1),
_semSpin(1)
{
_threadROS.start(callback(this, &HLComms::ros_main));// Start ROS thread
_rosReady.wait();
}
/*HLComms::~HLComms(void) { // Destructor
delete *_text_pub;
delete *_sensor_pub;
delete *_duration_pub;
}*/
// ROS
void HLComms::ros_main(void) {
_nh.getHardware()->setBaud(BAUD_RATE);
_nh.initNode();
wait_ms(1000);
ros::Subscriber<std_msgs::Int16MultiArray,HLComms> demands_sub("ML_Demands", &HLComms::receive_demands, this);
_nh.subscribe(demands_sub);
_text_pub = new ros::Publisher("ML_TextOut", &_text_msg);
_nh.advertise(*_text_pub);
_sensor_msg.data_length = N_CHANNELS*2;
_sensor_pub = new ros::Publisher("ML_Sensors", &_sensor_msg);
_nh.advertise(*_sensor_pub);
_duration_pub = new ros::Publisher("ML_Duration", &_duration_msg);
_nh.advertise(*_duration_pub);
wait_ms(1000);
_rosReady.release();
Ticker spinTicker;
spinTicker.attach(callback(this,&HLComms::releaseSemSpin), 1/(float)_freq_hz); // Set up HL comms to recur at fixed intervals
while (1) {
_semSpin.wait();
_nh.spinOnce();
}
}
void HLComms::releaseSemSpin(void) {
_semSpin.release();
}
// INPUT
void HLComms::receive_demands(const std_msgs::Int16MultiArray &demands_array) {
struct demands_struct _protected_input;
recv_mutex.lock();
for(int i=0; i<N_CHANNELS; i++) {
_protected_input.psi_mm[i] = MAX_ACTUATOR_LIMIT_MM*((double)demands_array.data[i]/511);
_protected_input.psi_mm[i] = min( max(_protected_input.psi_mm[i],0.0) , (double)MAX_ACTUATOR_LIMIT_MM );
}
//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
//short int demands_array_length = sizeof(demands_array.data)/sizeof(demands_array.data[0]);
//_protected_input.speed_mmps = demands_array.data[demands_array_length-1];
_protected_input.speed_mmps = MAX_SPEED_MMPS*((double)demands_array.data[9]/511);
_protected_input.speed_mmps = min( max(_protected_input.speed_mmps,0.0) , (double)MAX_SPEED_MMPS );
recv_mutex.unlock();
_input = _protected_input;
/*char array[20];
sprintf(array, "Speed: %f", _input.speed_mmps);
send_text_message(array);
sprintf(array, "Psi[0]: %f", _input.psi_mm[0]);
send_text_message(array);
sprintf(array, "Psi[1]: %f", _input.psi_mm[1]);
send_text_message(array);*/
newData.release();
}
demands_struct HLComms::get_demands(void) {
return _input;
}
// OUTPUT
void HLComms::send_text_message(char text[]) {
_text_msg.data = text;
_text_pub->publish(&_text_msg);
}
void HLComms::send_duration_message(double dblTime) {
_duration_msg.data = dblTime;
_duration_pub->publish(&_duration_msg);
}
void HLComms::send_sensor_message(unsigned int positions[], unsigned int pressures[]) {
short int i_channel;
for(short int i=0; i<N_CHANNELS*2; i++) {
i_channel = i%N_CHANNELS;
if(i<N_CHANNELS) {
_sensor_msg.data[i] = positions[i_channel];
} else {
_sensor_msg.data[i] = pressures[i_channel];
}
}
_sensor_pub->publish(&_sensor_msg);
}