|
| 1 | +#ifdef THRUSTER_TESTS_H |
| 2 | + |
| 3 | +#include "thruster_tests_main.h" |
| 4 | + |
| 5 | +#include <Arduino.h> |
| 6 | + |
| 7 | +#include <ros.h> |
| 8 | +#include <auv_msgs/ThrusterMicroseconds.h> |
| 9 | +#include <std_msgs/Float32.h> |
| 10 | + |
| 11 | +#define LED_PIN 13 |
| 12 | +#define BUTTON 2 |
| 13 | + |
| 14 | +float thrusterForce = -1; |
| 15 | + |
| 16 | +#define YELLOW_LED 6 |
| 17 | +#define GREEN_LED 7 |
| 18 | + |
| 19 | +// sensor code |
| 20 | +#include <HX711_ADC.h> |
| 21 | + |
| 22 | +const int HX711_dout = 4; // mcu > HX711 dout pin |
| 23 | +const int HX711_sck = 5; // mcu > HX711 sck pin |
| 24 | + |
| 25 | +HX711_ADC LoadCell(HX711_dout, HX711_sck); |
| 26 | + |
| 27 | +const int calVal_eepromAdress = 0; |
| 28 | +unsigned long t = 0; |
| 29 | + |
| 30 | +void sensor_setup() { |
| 31 | + LoadCell.begin(); |
| 32 | + float calibrationValue; |
| 33 | + calibrationValue = 178.6; |
| 34 | + unsigned long stabilizingtime = 2000; |
| 35 | + boolean _tare = true; |
| 36 | + LoadCell.start(stabilizingtime, _tare); |
| 37 | + if (LoadCell.getTareTimeoutFlag()) { |
| 38 | + while (1); |
| 39 | + } else { |
| 40 | + LoadCell.setCalFactor(calibrationValue); |
| 41 | + } |
| 42 | +} |
| 43 | + |
| 44 | +void sensor_loop() { |
| 45 | + static boolean newDataReady = 0; |
| 46 | + const int serialPrintInterval = 0; |
| 47 | + |
| 48 | + if (LoadCell.update()) newDataReady = true; |
| 49 | + |
| 50 | + if (newDataReady) { |
| 51 | + if (millis() > t + serialPrintInterval) { |
| 52 | + float i = LoadCell.getData(); |
| 53 | + thrusterForce = i; |
| 54 | + newDataReady = 0; |
| 55 | + t = millis(); |
| 56 | + } |
| 57 | + } |
| 58 | + |
| 59 | + if (digitalRead(BUTTON) == HIGH) { |
| 60 | + LoadCell.tareNoDelay(); |
| 61 | + digitalWrite(YELLOW_LED, HIGH); |
| 62 | + } |
| 63 | + |
| 64 | + if (LoadCell.getTareStatus() == true) { |
| 65 | + digitalWrite(GREEN_LED, HIGH); |
| 66 | + delay(500); |
| 67 | + digitalWrite(YELLOW_LED, LOW); |
| 68 | + digitalWrite(GREEN_LED, LOW); |
| 69 | + } |
| 70 | +} |
| 71 | +// end of sensor code |
| 72 | + |
| 73 | +std_msgs::Float32 thruster_force_msg; |
| 74 | + |
| 75 | +uint16_t microseconds[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500}; |
| 76 | +void commandCb(const auv_msgs::ThrusterMicroseconds &tc) { |
| 77 | + memcpy(microseconds, tc.microseconds, 8 * sizeof(uint16_t)); |
| 78 | +} |
| 79 | + |
| 80 | +ros::NodeHandle nh; |
| 81 | +ros::Subscriber<auv_msgs::ThrusterMicroseconds> sub("/propulsion/microseconds", &commandCb); |
| 82 | +ros::Publisher thruster_force("/thruster/force", &thruster_force_msg); |
| 83 | + |
| 84 | +void publishData() { |
| 85 | + thruster_force_msg.data = thrusterForce; |
| 86 | + thruster_force.publish(&thruster_force_msg); |
| 87 | +} |
| 88 | + |
| 89 | +void thruster_tests_setup() { |
| 90 | + pinMode(BUTTON, INPUT); |
| 91 | + pinMode(YELLOW_LED, OUTPUT); |
| 92 | + pinMode(GREEN_LED, OUTPUT); |
| 93 | + pinMode(LED_PIN, OUTPUT); |
| 94 | + digitalWrite(LED_PIN, HIGH); |
| 95 | + |
| 96 | + sensor_setup(); |
| 97 | + |
| 98 | + nh.initNode(); |
| 99 | + nh.subscribe(sub); |
| 100 | + nh.advertise(thruster_force); |
| 101 | +} |
| 102 | + |
| 103 | +void thruster_tests_loop() { |
| 104 | + digitalWrite(LED_PIN, !digitalRead(LED_PIN)); |
| 105 | + |
| 106 | + sensor_loop(); |
| 107 | + |
| 108 | + publishData(); |
| 109 | + nh.spinOnce(); |
| 110 | + delay(10); |
| 111 | +} |
| 112 | + |
| 113 | +#endif |
0 commit comments