semin ahn / Mbed OS zeta_stm_kinetic

Dependencies:   BufferedSerial

Committer:
_seminahn
Date:
Tue Nov 30 08:13:05 2021 +0000
Revision:
3:a4677501ae87
Parent:
2:0de4854743f7
v1.2.5, change imu freq

Who changed what in which revision?

UserRevisionLine numberNew contents of line
_seminahn 0:4ff8aeb3e4d1 1 #ifndef ZETA_STM_KINETIC_INITFUNCTION_H_
_seminahn 0:4ff8aeb3e4d1 2 #define ZETA_STM_KINETIC_INITFUNCTION_H_
_seminahn 0:4ff8aeb3e4d1 3 #include "mbed.h"
_seminahn 0:4ff8aeb3e4d1 4 #include "threadDeclaration.hpp"
_seminahn 3:a4677501ae87 5 #include "variables/instanceHeader.hpp"
_seminahn 0:4ff8aeb3e4d1 6 #include "rosHeader.hpp"
_seminahn 3:a4677501ae87 7 #include "configurations/robotConfig.h"
_seminahn 0:4ff8aeb3e4d1 8 void initThread() {
_seminahn 3:a4677501ae87 9 int index = 0;
_seminahn 3:a4677501ae87 10 gThread[index++].start(IMU_thread);
_seminahn 3:a4677501ae87 11 gThread[index++].start(bt_thread);
_seminahn 3:a4677501ae87 12 gThread[index++].start(sonar_thread);
_seminahn 3:a4677501ae87 13 gThread[index++].start(sonar_pub_thread);
_seminahn 3:a4677501ae87 14 gThread[index++].start(bt_pub_thread);
_seminahn 3:a4677501ae87 15 #ifdef NO_ROS
_seminahn 3:a4677501ae87 16 gThread[index++].start(print_thread);
_seminahn 3:a4677501ae87 17 #else
_seminahn 1:2594a70c1ddd 18 //gThread[3].start(module_thread);
_seminahn 3:a4677501ae87 19 gThread[index++].start(imu_pub_thread);
_seminahn 3:a4677501ae87 20 gThread[index++].start(estop_pub_thread);
_seminahn 3:a4677501ae87 21 #if (ROBOT_TYPE == MODEL_D)
_seminahn 3:a4677501ae87 22 gThread[index++].start(level_sensor_thread);
_seminahn 3:a4677501ae87 23 #endif
_seminahn 3:a4677501ae87 24 #if (ROBOT_TYPE == MODEL_I)
_seminahn 3:a4677501ae87 25 gThread[index++].start(lidar_dusty_pub_thread);
_seminahn 3:a4677501ae87 26 #endif
_seminahn 3:a4677501ae87 27 #endif /* #ifdef NO_ROS */
_seminahn 1:2594a70c1ddd 28 //gThread[8].start(test_thread);
_seminahn 0:4ff8aeb3e4d1 29 }
_seminahn 0:4ff8aeb3e4d1 30
_seminahn 0:4ff8aeb3e4d1 31 void initBT() {
_seminahn 0:4ff8aeb3e4d1 32 bt.baud(9600);
_seminahn 0:4ff8aeb3e4d1 33 bt_data.rec = '\0';
_seminahn 0:4ff8aeb3e4d1 34 bt_data.sen = '\0';
_seminahn 0:4ff8aeb3e4d1 35 }
_seminahn 0:4ff8aeb3e4d1 36
_seminahn 3:a4677501ae87 37 #ifdef NO_ROS
_seminahn 0:4ff8aeb3e4d1 38 void initSerial() {
_seminahn 0:4ff8aeb3e4d1 39 pc.baud(115200);
_seminahn 0:4ff8aeb3e4d1 40 }
_seminahn 3:a4677501ae87 41 #else
_seminahn 0:4ff8aeb3e4d1 42 void initROS() {
_seminahn 3:a4677501ae87 43 nh.getHardware()->setBaud(ROSSERIAL_BUADRATE);
_seminahn 0:4ff8aeb3e4d1 44 nh.initNode();
_seminahn 3:a4677501ae87 45 US_msg.data = (float*)malloc(sizeof(float) * NUM_SONAR);
_seminahn 3:a4677501ae87 46 US_msg.data_length = NUM_SONAR;
_seminahn 0:4ff8aeb3e4d1 47 nh.advertise(IMU_publisher);
_seminahn 0:4ff8aeb3e4d1 48 nh.advertise(EStop_publisher);
_seminahn 3:a4677501ae87 49 //nh.advertise(Bumper_publisher);
_seminahn 0:4ff8aeb3e4d1 50 nh.advertise(US_publisher);
_seminahn 0:4ff8aeb3e4d1 51 nh.advertise(Bluetooth_publisher);
_seminahn 0:4ff8aeb3e4d1 52 nh.subscribe(Bluetooth_subscriber);
_seminahn 3:a4677501ae87 53 nh.subscribe(SsrTest_subscriber);
_seminahn 3:a4677501ae87 54 #if (ROBOT_TYPE == MODEL_D)
_seminahn 3:a4677501ae87 55 nh.advertise(water_level_publisher);
_seminahn 3:a4677501ae87 56 #endif
_seminahn 3:a4677501ae87 57 #if (ROBOT_TYPE == MODEL_I)
_seminahn 3:a4677501ae87 58 nh.subscribe(ScrubberControl_subscriber);
_seminahn 3:a4677501ae87 59 nh.advertise(LidarDusty_publisher);
_seminahn 3:a4677501ae87 60 nh.advertise(EmergencyStop_publisher);
_seminahn 3:a4677501ae87 61 nh.subscribe(WarningFieldSelect_subscriber);
_seminahn 3:a4677501ae87 62 nh.subscribe(IgnoreWarningField_subscriber);
_seminahn 3:a4677501ae87 63 #endif
_seminahn 0:4ff8aeb3e4d1 64 while(!nh.connected()) nh.spinOnce();
_seminahn 0:4ff8aeb3e4d1 65 waitTmr.start();
_seminahn 3:a4677501ae87 66 nh.loginfo(__FW_VERSION__);
_seminahn 0:4ff8aeb3e4d1 67 }
_seminahn 3:a4677501ae87 68 #endif
_seminahn 0:4ff8aeb3e4d1 69
_seminahn 2:0de4854743f7 70 #endif