Skip to content

Commit 0b516a1

Browse files
authored
Merge thruster test code #153
Thruster tests code - Updated power board code to publish all thruster test data on single array - Dockerfile to run all thruster test dependencies - Arduino code to get data from load cell connected to thruster - Update to ADC code to make it MCU blind
2 parents 9f80edb + faa1985 commit 0b516a1

37 files changed

+1309
-1
lines changed
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
#ifdef THRUSTER_TESTS_H
2+
3+
#include <Arduino.h>
4+
5+
void thruster_tests_setup();
6+
void thruster_tests_loop();
7+
8+
#endif

pio_workspace/lib/power_custom/adc_sensors.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ class ADCSensors {
2222
ADCSensors();
2323

2424
// Initialization of ADCSensor
25-
bool begin(bool enableVoltage, bool enableCurrent, TwoWire* wire = &Wire1);
25+
bool begin(bool enableVoltage, bool enableCurrent, TwoWire* wire);
2626

2727
// Returns an array pointer to current measurements
2828
float* senseVoltage();

pio_workspace/platformio.ini

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,3 +74,13 @@ build_flags =
7474
${env.build_flags}
7575
#upload_protocol = teensy-cli
7676
upload_port = /dev/power
77+
78+
[env:thruster_tests]
79+
platform = atmelavr
80+
board = uno
81+
framework = arduino
82+
build_flags =
83+
-D THRUSTER_TESTS_H
84+
lib_ignore = micro_ros_arduino
85+
monitor_speed= 57600
86+
lib_deps = HX711_ADC

pio_workspace/src/main.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
1010
#include "power_main.h"
1111
#elif POWER_ROS1_H
1212
#include "power_ros1_main.h"
13+
#elif THRUSTER_TESTS_H
14+
#include "thruster_tests_main.h"
1315
#endif
1416

1517
void setup() {
@@ -23,6 +25,8 @@ void setup() {
2325
power_setup();
2426
#elif POWER_ROS1_H
2527
power_ros1_setup();
28+
#elif THRUSTER_TESTS_H
29+
thruster_tests_setup();
2630
#endif
2731
}
2832

@@ -37,5 +41,7 @@ void loop() {
3741
power_loop();
3842
#elif POWER_ROS1_H
3943
power_ros1_loop();
44+
#elif THRUSTER_TESTS_H
45+
thruster_tests_loop();
4046
#endif
4147
}
Lines changed: 113 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,113 @@
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
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
# Start from the ROS Noetic base image
2+
FROM ros:noetic
3+
4+
# Set noninteractive frontend for apt
5+
ENV DEBIAN_FRONTEND=noninteractive
6+
7+
# Update package lists and install necessary packages
8+
RUN apt update && \
9+
apt install -y tmux git vim \
10+
ros-noetic-rosserial ros-noetic-rosserial-arduino python3-catkin-tools && \
11+
rm -rf /var/lib/apt/lists/*
12+
13+
# Source ROS setup
14+
RUN echo "source /opt/ros/noetic/setup.bash" >> /root/.bashrc
15+
16+
# Default command
17+
CMD ["bash"]
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
build
2+
logs
3+
devel
4+
.catkin_tools
5+
src/propulsion/src/__pycache__
Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
cmake_minimum_required(VERSION 3.0.2)
2+
project(auv_msgs)
3+
4+
# set of packages whose message types are used
5+
set(MSG_DEP_SET
6+
actionlib_msgs
7+
geometry_msgs
8+
std_msgs
9+
)
10+
11+
12+
find_package(catkin REQUIRED COMPONENTS
13+
${MSG_DEP_SET}
14+
message_generation
15+
)
16+
17+
add_message_files(FILES
18+
ThrusterMicroseconds.msg
19+
ThrusterForces.msg
20+
PingerBearing.msg
21+
PingerTimeDifference.msg
22+
VisionObject.msg
23+
VisionObjectArray.msg
24+
DeadReckonReport.msg
25+
VelocityReport.msg
26+
UnityState.msg
27+
)
28+
29+
30+
add_action_files(FILES
31+
StateQuaternion.action
32+
Effort.action
33+
)
34+
35+
generate_messages(DEPENDENCIES
36+
${MSG_DEP_SET}
37+
)
38+
39+
catkin_package(CATKIN_DEPENDS
40+
${MSG_DEP_SET}
41+
message_runtime
42+
)
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
# goal
2+
geometry_msgs/Wrench effort
3+
std_msgs/Bool do_surge
4+
std_msgs/Bool do_sway
5+
std_msgs/Bool do_heave
6+
std_msgs/Bool do_roll
7+
std_msgs/Bool do_pitch
8+
std_msgs/Bool do_yaw
9+
---
10+
# result
11+
std_msgs/Bool stopped
12+
---
13+
# feedback
14+
std_msgs/Bool moving
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
# goal
2+
geometry_msgs/Pose pose
3+
std_msgs/Bool do_x
4+
std_msgs/Bool do_y
5+
std_msgs/Bool do_z
6+
std_msgs/Bool do_quaternion
7+
std_msgs/Bool displace
8+
std_msgs/Bool local
9+
---
10+
# result
11+
std_msgs/Bool status
12+
---
13+
# feedback
14+
std_msgs/Bool status

0 commit comments

Comments
 (0)