semin ahn / Mbed OS zeta_stm_kinetic

Dependencies:   BufferedSerial

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers instanceHeader.hpp Source File

instanceHeader.hpp

00001 #ifndef ZETA_STM_KINETIC_INSTANCEHEADER_H_
00002 #define ZETA_STM_KINETIC_INSTANCEHEADER_H_
00003 #include "mbed.h"
00004 #include "src/rosHeader.hpp"
00005 #include "src/moduleHeader.hpp"
00006 #include "src/callbackHeader.hpp"
00007 #include "defineHeader.h"
00008 #include "configurations/robotConfig.h"
00009 /* COM variables ------------------------------------------------------------ */
00010 #if (NO_ROS)
00011 extern mbed::Serial pc;
00012 #else
00013 extern ros::NodeHandle nh;
00014 #endif
00015 extern mbed::Serial bt;
00016 
00017 /* ROS variables ------------------------------------------------------------ */
00018 // Publisher
00019 //zetabot_main::SonarArray US_msg;
00020 //ros::Publisher US_publisher("sonar", &US_msg);
00021 std_msgs::String version_msg;
00022 ros::Publisher version_publisher("stm_version", &version_msg);
00023 
00024 std_msgs::Float32MultiArray US_msg;
00025 ros::Publisher US_publisher("sonar", &US_msg);
00026 
00027 std_msgs::String Bluetooth_msg;
00028 ros::Publisher Bluetooth_publisher("autocharge_state_INO", &Bluetooth_msg);
00029 
00030 #if (ROBOT_TYPE == MODEL_D)
00031 //std_msgs::UInt8 water_level_msg;
00032 //ros::Publisher water_level_publisher("water_level", &water_level_msg);
00033 std_msgs::Bool water_level_msg;
00034 ros::Publisher water_level_publisher("water_level", &water_level_msg);
00035 #endif
00036 
00037 #if (ROBOT_TYPE == MODEL_I)
00038 std_msgs::Bool lidar_dusty_msg;
00039 ros::Publisher LidarDusty_publisher("LidarDusty", &lidar_dusty_msg);
00040 
00041 std_msgs::UInt8 emergency_stop_msg;
00042 ros::Publisher EmergencyStop_publisher("EmergencyStop", &emergency_stop_msg);
00043 #endif
00044 
00045 sensor_msgs::Imu imu_msg;
00046 ros::Publisher IMU_publisher("imu", &imu_msg);
00047 
00048 std_msgs::Bool EStop_msg;
00049 ros::Publisher EStop_publisher("estop", &EStop_msg);
00050 
00051 std_msgs::Bool Bumper_msg;
00052 ros::Publisher Bumper_publisher("bumper", &Bumper_msg);
00053 
00054 
00055 // Subscriber
00056 void BluetoothCB(const std_msgs::UInt8& msg);
00057 ros::Subscriber<std_msgs::UInt8> Bluetooth_subscriber("autocharge_state_NUC", &BluetoothCB);
00058 
00059 void SsrTestCB(const std_msgs::Bool& msg);
00060 ros::Subscriber<std_msgs::Bool> SsrTest_subscriber("SsrControlTest", &SsrTestCB);
00061 
00062 #if (ROBOT_TYPE == MODEL_I)
00063 void WarningFieldSelectCB(const std_msgs::UInt8& msg);
00064 ros::Subscriber<std_msgs::UInt8> WarningFieldSelect_subscriber("WarningFieldSelect", &WarningFieldSelectCB);
00065 
00066 void IgnoreWarningFieldCB(const std_msgs::UInt8&);
00067 ros::Subscriber<std_msgs::UInt8> IgnoreWarningField_subscriber("IgnoreWarningField", &IgnoreWarningFieldCB);
00068 
00069 void ScrubberControlCB(const std_msgs::Bool& msg);
00070 ros::Subscriber<std_msgs::Bool> ScrubberControl_subscriber("ScrubberControl", &ScrubberControlCB);
00071 #endif
00072 /* Threads and Timers ------------------------------------------------------- */
00073 Thread gThread[NUM_THREAD];
00074 
00075 Timer waitTmr;
00076 
00077 
00078 /* Modules ------------------------------------------------------------------ */
00079 MPU9250_SPI mpu(IMU_MOSI, IMU_MISO, IMU_SCK, IMU_NCS, IMU_INT);
00080 
00081 #if ((ROBOT_TYPE == MODEL_C) || (ROBOT_TYPE == MODEL_D))
00082 ChargingControl charging_control(CHARGE_RELAYP, CHARGE_RELAYN);
00083 DigitalIn estop(EMERGENCY_STOP);
00084 PinName echo[NUM_SONAR] = {RS_ECH01, RS_ECH02, RS_ECH03, RS_ECH04, RS_ECH05, RS_ECH06, RS_ECH07, RU_ECH01, RU_ECH02, RU_ECH03};
00085 SONAR_MANAGER<NUM_SONAR> sonar_manager(echo, TRIG);
00086 #elif (ROBOT_TYPE == MODEL_I)
00087 PinName echo[NUM_SONAR] = {SONAR_LEFT, SONAR_RIGHT};
00088 SONAR_MANAGER<NUM_SONAR> sonar_manager(echo, SONAR_TRIG);
00089 #endif
00090 
00091 #if (ROBOT_TYPE == MODEL_D)
00092 //DigitalIn level_blue(LEVEL_SENSE1);
00093 //DigitalIn level_yellow(LEVEL_SENSE2);
00094 DigitalIn level_sensor(LEVEL_SENSE);
00095 #endif
00096 
00097 #if (ROBOT_TYPE == MODEL_I)
00098 DigitalOut ChargingSsr(SSR_CTRL, 0);
00099 DigitalOut ScrubberControl(SCRUBBER_CTRL, 0);
00100 DigitalOut WaringFieldSelectPin1(LIDAR_WARNING1, 1);
00101 DigitalOut WaringFieldSelectPin2(LIDAR_WARNING2, 1);
00102 DigitalOut IgnoreWarningFieldPin1(IGNORE_WARNING1, 0);
00103 DigitalOut IgnoreWarningFieldPin2(IGNORE_WARNING2, 0);
00104 DigitalIn LidarDustSensingPin(LIDAR_DUSTSENSING);
00105 DigitalIn EmergencyStopPin(EMERGENCY_STOP);
00106 DigitalIn LidarStopPin(LIDAR_DETECT_OBSTACLE);
00107 #endif
00108 
00109 //EStop estop(EMERGENCY);
00110 
00111 /* For test ----------------------------------------------------------------- */
00112 
00113 #endif