4
4
#include < std_msgs/Float32.h>
5
5
6
6
// defines thruster pins
7
- #define FRONT_L_PIN 2
8
- #define FRONT_R_PIN 3
9
- #define BACK_L_PIN 4
10
- #define BACK_R_PIN 5
11
- #define HEAVE_FRONT_L_PIN 6
7
+ #define BACK_L_PIN 2
8
+ #define HEAVE_BACK_L_PIN 3
9
+ #define HEAVE_FRONT_L_PIN 4
10
+ #define FRONT_L_PIN 5
11
+ #define FRONT_R_PIN 6
12
12
#define HEAVE_FRONT_R_PIN 7
13
- #define HEAVE_BACK_L_PIN 8
14
- #define HEAVE_BACK_R_PIN 9
13
+ #define HEAVE_BACK_R_PIN 8
14
+ #define BACK_R_PIN 9
15
15
16
16
// defines voltage sensing pins
17
17
#define VBAT1_SENSE 22
18
18
#define VBAT2_SENSE 23
19
19
20
20
// defines 8 thursters for ROS subscribing
21
- const uint8_t FRONT_L = auv_msgs::ThrusterMicroseconds::FRONT_LEFT;
22
- const uint8_t FRONT_R = auv_msgs::ThrusterMicroseconds::FRONT_RIGHT;
23
21
const uint8_t BACK_L = auv_msgs::ThrusterMicroseconds::BACK_LEFT;
24
- const uint8_t BACK_R = auv_msgs::ThrusterMicroseconds::BACK_RIGHT ;
22
+ const uint8_t HEAVE_BACK_L = auv_msgs::ThrusterMicroseconds::HEAVE_BACK_LEFT ;
25
23
const uint8_t HEAVE_FRONT_L = auv_msgs::ThrusterMicroseconds::HEAVE_FRONT_LEFT;
24
+ const uint8_t FRONT_L = auv_msgs::ThrusterMicroseconds::FRONT_LEFT;
25
+ const uint8_t FRONT_R = auv_msgs::ThrusterMicroseconds::FRONT_RIGHT;
26
26
const uint8_t HEAVE_FRONT_R = auv_msgs::ThrusterMicroseconds::HEAVE_FRONT_RIGHT;
27
- const uint8_t HEAVE_BACK_L = auv_msgs::ThrusterMicroseconds::HEAVE_BACK_LEFT;
28
27
const uint8_t HEAVE_BACK_R = auv_msgs::ThrusterMicroseconds::HEAVE_BACK_RIGHT;
28
+ const uint8_t BACK_R = auv_msgs::ThrusterMicroseconds::BACK_RIGHT;
29
29
30
30
// defines 2 battery voltage sensing for ROS advertising
31
31
std_msgs::Float32 batt1_voltage_msg;
@@ -43,14 +43,14 @@ float Bvoltages[2];
43
43
44
44
// updates thrusters' pwm signals from array
45
45
void updateThrusters (const uint16_t microseconds[8 ]) {
46
- thrusters[FRONT_L].writeMicroseconds (microseconds[FRONT_L]);
47
- thrusters[FRONT_R].writeMicroseconds (microseconds[FRONT_R]);
48
46
thrusters[BACK_L].writeMicroseconds (microseconds[BACK_L]);
49
- thrusters[BACK_R ].writeMicroseconds (microseconds[BACK_R ]);
47
+ thrusters[HEAVE_BACK_L ].writeMicroseconds (microseconds[HEAVE_BACK_L ]);
50
48
thrusters[HEAVE_FRONT_L].writeMicroseconds (microseconds[HEAVE_FRONT_L]);
49
+ thrusters[FRONT_L].writeMicroseconds (microseconds[FRONT_L]);
50
+ thrusters[FRONT_R].writeMicroseconds (microseconds[FRONT_R]);
51
51
thrusters[HEAVE_FRONT_R].writeMicroseconds (microseconds[HEAVE_FRONT_R]);
52
+ thrusters[BACK_R].writeMicroseconds (microseconds[BACK_R]);
52
53
thrusters[HEAVE_BACK_R].writeMicroseconds (microseconds[HEAVE_BACK_R]);
53
- thrusters[HEAVE_BACK_L].writeMicroseconds (microseconds[HEAVE_BACK_L]);
54
54
}
55
55
56
56
// updates microseconds array with values from ros
@@ -60,14 +60,14 @@ void commandCb(const auv_msgs::ThrusterMicroseconds &tc) {
60
60
61
61
// attaches and arms thrusters
62
62
void initThrusters () {
63
- thrusters[FRONT_L].attach (FRONT_L_PIN);
64
- thrusters[FRONT_R].attach (FRONT_R_PIN);
65
63
thrusters[BACK_L].attach (BACK_L_PIN);
66
- thrusters[BACK_R ].attach (BACK_R_PIN );
64
+ thrusters[HEAVE_BACK_L ].attach (HEAVE_BACK_L_PIN );
67
65
thrusters[HEAVE_FRONT_L].attach (HEAVE_FRONT_L_PIN);
66
+ thrusters[FRONT_L].attach (FRONT_L_PIN);
67
+ thrusters[FRONT_R].attach (FRONT_R_PIN);
68
68
thrusters[HEAVE_FRONT_R].attach (HEAVE_FRONT_R_PIN);
69
- thrusters[HEAVE_BACK_L].attach (HEAVE_BACK_L_PIN);
70
69
thrusters[HEAVE_BACK_R].attach (HEAVE_BACK_R_PIN);
70
+ thrusters[BACK_R].attach (BACK_R_PIN);
71
71
72
72
updateThrusters (offCommand);
73
73
}
0 commit comments