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.
callbackHeader.hpp
00001 #ifndef ZETA_STM_KINETIC_CALLBACKHEADER_H_ 00002 #define ZETA_STM_KINETIC_CALLBACKHEADER_H_ 00003 #include "rosHeader.hpp" 00004 #include "mbed.h" 00005 #include "myUtil.hpp" 00006 #include "configurations/robotConfig.h" 00007 //extern std_msgs::Bool UVCcontrolMsg; 00008 extern volatile bool isSubscribe; 00009 extern volatile uint8_t NUC_sub_state; 00010 extern ros::NodeHandle nh; 00011 #if ((ROBOT_TYPE == MODEL_C) || (ROBOT_TYPE == MODEL_D)) 00012 extern ChargingControl charging_control; 00013 #endif 00014 #if (ROBOT_TYPE == MODEL_I) 00015 extern DigitalOut WaringFieldSelectPin1; 00016 extern DigitalOut WaringFieldSelectPin2; 00017 extern DigitalOut IgnoreWarningFieldPin1; 00018 extern DigitalOut IgnoreWarningFieldPin2; 00019 extern DigitalOut ScrubberControl; 00020 extern DigitalOut ChargingSsr; 00021 #endif 00022 00023 void BluetoothCB(const std_msgs::UInt8& msg) 00024 { 00025 NUC_sub_state = msg.data; 00026 } 00027 00028 void SsrTestCB(const std_msgs::Bool& msg) 00029 { 00030 #if ((ROBOT_TYPE == MODEL_C) || (ROBOT_TYPE == MODEL_D)) 00031 if(msg.data) 00032 { 00033 charging_control.on(); 00034 } 00035 else 00036 { 00037 charging_control.off(); 00038 } 00039 #elif (ROBOT_TYPE == MODEL_I) 00040 ChargingSsr = msg.data; 00041 #endif 00042 ThisThread::sleep_for(1000); 00043 } 00044 00045 00046 #if (ROBOT_TYPE == MODEL_I) 00047 void WarningFieldSelectCB(const std_msgs::UInt8& msg) 00048 { 00049 const unsigned char pos_front = 0U; 00050 const unsigned char pos_rear = 1U; 00051 enum warning_field_select_enum 00052 { 00053 field1 = 0, 00054 field2, 00055 }; 00056 if(msg.data & (1U << pos_front)) 00057 { 00058 WaringFieldSelectPin1 = 1; 00059 } 00060 else 00061 { 00062 WaringFieldSelectPin1 = 0; 00063 } 00064 if(msg.data & (1U << pos_rear)) 00065 { 00066 WaringFieldSelectPin2 = 1; 00067 } 00068 else 00069 { 00070 WaringFieldSelectPin2 = 0; 00071 } 00072 } 00073 00074 void IgnoreWarningFieldCB(const std_msgs::UInt8& msg) 00075 { 00076 const unsigned char pos_front = 0U; 00077 const unsigned char pos_rear = 1U; 00078 enum warning_field_select_enum 00079 { 00080 field1 = 0, 00081 field2, 00082 }; 00083 if(msg.data & (1U << pos_front)) 00084 { 00085 IgnoreWarningFieldPin1 = 1; 00086 } 00087 else 00088 { 00089 IgnoreWarningFieldPin1 = 0; 00090 } 00091 if(msg.data & (1U << pos_rear)) 00092 { 00093 IgnoreWarningFieldPin2 = 1; 00094 } 00095 else 00096 { 00097 IgnoreWarningFieldPin2 = 0; 00098 } 00099 } 00100 void ScrubberControlCB(const std_msgs::Bool& msg) 00101 { 00102 if(msg.data) 00103 { 00104 ScrubberControl = 1; 00105 } 00106 else 00107 { 00108 ScrubberControl = 0; 00109 } 00110 } 00111 #endif 00112 #endif
Generated on Tue Jul 12 2022 18:31:23 by
1.7.2