1
+ /*
2
+ Revision 1.0
3
+
4
+ SETUP FOR ROS COMMUNICATION WITH THE POWER BOARD
5
+ 1) Initializes and connects thrusters, adc sensors, and temperature sensors
6
+ 2) Sets up ros nodes for advertising and subscribing
7
+ 3) Polls all sensors, publishes data, and updates thrusters every 10 ms
8
+ */
9
+
1
10
#ifdef POWER_ROS1_H
2
11
3
12
#include " power_ros1_main.h"
29
38
#define ENABLE_VOLTAGE_SENSE true
30
39
#define ENABLE_CURRENT_SENSE true
31
40
41
+ // creates ADCSensors and TMP36 sensor objects
32
42
ADCSensors adcSensors;
33
43
TMP36 temperatureSensor (23 , 3.3 );
34
44
35
- // defines 8 thursters for ROS subscribing
45
+ // defines 8 thrusters for ROS subscribing
36
46
const uint8_t BACK_L = auv_msgs::ThrusterMicroseconds::BACK_LEFT;
37
47
const uint8_t HEAVE_BACK_L = auv_msgs::ThrusterMicroseconds::HEAVE_BACK_LEFT;
38
48
const uint8_t HEAVE_FRONT_L = auv_msgs::ThrusterMicroseconds::HEAVE_FRONT_LEFT;
@@ -46,6 +56,7 @@ const uint8_t BACK_R = auv_msgs::ThrusterMicroseconds::BACK_RIGHT;
46
56
std_msgs::Float32 batt1_voltage_msg;
47
57
std_msgs::Float32 batt2_voltage_msg;
48
58
59
+ // defines 8 thruster current sensing for ROS advertising
49
60
std_msgs::Float32 thruster1_current_msg;
50
61
std_msgs::Float32 thruster2_current_msg;
51
62
std_msgs::Float32 thruster3_current_msg;
@@ -55,6 +66,7 @@ std_msgs::Float32 thruster6_current_msg;
55
66
std_msgs::Float32 thruster7_current_msg;
56
67
std_msgs::Float32 thruster8_current_msg;
57
68
69
+ // defines board and teensy temperature sensing for ROS advertising
58
70
std_msgs::Float32 board_temperature_msg;
59
71
std_msgs::Float32 teensy_temperature_msg;
60
72
@@ -65,9 +77,8 @@ Servo thrusters[8];
65
77
uint16_t microseconds[] = {1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 };
66
78
const uint16_t offCommand[] = {1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 };
67
79
68
- // creates array for 2 battery voltage sensing
69
- float Bvoltages[2 ];
70
- float Tcurrents[8 ];
80
+ float Bvoltages[2 ]; // array for 2 battery voltage sensing
81
+ float Tcurrents[8 ]; // array for 8 thrusters current sensing
71
82
float boardTemperature;
72
83
float teensyTemperature;
73
84
@@ -118,7 +129,7 @@ ros::Publisher thruster8_current("/power/thrusters/current/8", &thruster8_curren
118
129
ros::Publisher board_temperature (" /power/board/temperature" , &board_temperature_msg);
119
130
ros::Publisher teensy_temperature (" /power/teensy/temperature" , &teensy_temperature_msg);
120
131
121
- // senses the voltages of the 2 batteries
132
+ // senses the battery voltages, thruster currents, and board and teensy temperatures
122
133
void senseData () {
123
134
float * voltagePtr = adcSensors.senseVoltage ();
124
135
float * currentPtr = adcSensors.senseCurrent ();
@@ -171,9 +182,10 @@ void publishData() {
171
182
teensy_temperature.publish (&teensy_temperature_msg);
172
183
}
173
184
185
+ // setup all thrusters and sensors and setup node handler for subscribing and advertising
174
186
void power_ros1_setup () {
175
187
pinMode (LED_PIN, OUTPUT);
176
- digitalWrite (LED_PIN, HIGH);
188
+ digitalWrite (LED_PIN, HIGH); // turn on LED_PIN
177
189
178
190
initThrusters ();
179
191
@@ -197,7 +209,7 @@ void power_ros1_setup() {
197
209
}
198
210
199
211
void power_ros1_loop () {
200
- updateThrusters (microseconds);
212
+ updateThrusters (microseconds);
201
213
202
214
publishData ();
203
215
0 commit comments