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
Diff: HLComms.cpp
- Revision:
- 31:08cb04eb75fc
- Parent:
- 30:6c8eea90735e
- Child:
- 32:8c59c536a2a6
--- a/HLComms.cpp Fri Feb 15 10:29:23 2019 +0000
+++ b/HLComms.cpp Wed Mar 06 10:28:59 2019 +0000
@@ -16,7 +16,7 @@
/*HLComms::~HLComms(void) { // Destructor
delete *_text_pub;
delete *_sensor_pub;
- delete *_duration_pub;
+ delete *_durations_pub;
}*/
// ROS
@@ -37,8 +37,9 @@
_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);
+ _durations_msg.data_length = 3;
+ _durations_pub = new ros::Publisher("ML_Durations", &_durations_msg);
+ _nh.advertise(*_durations_pub);
wait_ms(1000);
_rosReady.release();
@@ -93,8 +94,12 @@
_protected_input.psi_mm[i] = min( max(_protected_input.psi_mm[i],0.0) , (double)MAX_ACTUATOR_LIMIT_MM );
}
}
- _protected_input.speed_mmps = (double)demands_array.data[9];
- _protected_input.speed_mmps = min( max(_protected_input.speed_mmps,0.0) , (double)MAX_SPEED_MMPS );
+ _protected_input.speeds_mmps[0] = (double)demands_array.data[9];
+ _protected_input.speeds_mmps[0] = min( max(_protected_input.speeds_mmps[0],0.0) , (double)MAX_SPEED_MMPS );
+ _protected_input.speeds_mmps[1] = (double)demands_array.data[10];
+ _protected_input.speeds_mmps[1] = min( max(_protected_input.speeds_mmps[1],0.0) , (double)MAX_SPEED_MMPS );
+ _protected_input.speeds_mmps[2] = (double)demands_array.data[11];
+ _protected_input.speeds_mmps[2] = min( max(_protected_input.speeds_mmps[2],0.0) , (double)MAX_SPEED_MMPS );
recv_mutex.unlock();
_input = _protected_input;
newData.release();
@@ -111,9 +116,11 @@
_text_pub->publish(&_text_msg);
}
-void HLComms::send_duration_message(double dblTime) {
- _duration_msg.data = dblTime;
- _duration_pub->publish(&_duration_msg);
+void HLComms::send_durations_message(double dblTimes[]) {
+ for(short int i=0; i<3; i++) {
+ _durations_msg.data[i] = dblTimes[i];
+ }
+ _durations_pub->publish(&_durations_msg);
}
void HLComms::send_sensor_message(unsigned int positions[], unsigned int pressures[]) {