
Mid level control code
Dependencies: ros_lib_kinetic
Diff: HLComms.cpp
- Revision:
- 36:4459be8296e9
- Parent:
- 33:9877ca32e43c
--- a/HLComms.cpp Mon Apr 15 15:12:51 2019 +0000 +++ b/HLComms.cpp Tue Jul 09 18:46:44 2019 +0000 @@ -59,30 +59,6 @@ // 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+1.0)*((double)demands_array.data[i]/65535)-1.0); - if( _protected_input.psi_mm[i]<-0.5 ) { - _protected_input.psi_mm[i] = -1.0; - } else { - _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]/65535); - _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); - newData.release(); -}*/ - void HLComms::receive_demands(const std_msgs::Float32MultiArray &demands_array) { struct demands_struct _protected_input; recv_mutex.lock(); @@ -90,7 +66,6 @@ _protected_input.psi_mm[i] = (double)demands_array.data[i]; //_protected_input.psi_mm[i] = min( max(_protected_input.psi_mm[i],0.0) , (double)MAX_ACTUATOR_LIMIT_MM ); } - // demands_array.data[8] ignored _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];