Skip to content

Commit 44e3dcc

Browse files
committed
updated code for ease of pull request merging with main
1 parent cca0b41 commit 44e3dcc

File tree

1 file changed

+19
-19
lines changed

1 file changed

+19
-19
lines changed

Power/src/main.cpp

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -4,28 +4,28 @@
44
#include <std_msgs/Float32.h>
55

66
// 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
1212
#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
1515

1616
// defines voltage sensing pins
1717
#define VBAT1_SENSE 22
1818
#define VBAT2_SENSE 23
1919

2020
// 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;
2321
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;
2523
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;
2626
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;
2827
const uint8_t HEAVE_BACK_R = auv_msgs::ThrusterMicroseconds::HEAVE_BACK_RIGHT;
28+
const uint8_t BACK_R = auv_msgs::ThrusterMicroseconds::BACK_RIGHT;
2929

3030
// defines 2 battery voltage sensing for ROS advertising
3131
std_msgs::Float32 batt1_voltage_msg;
@@ -43,14 +43,14 @@ float Bvoltages[2];
4343

4444
// updates thrusters' pwm signals from array
4545
void updateThrusters(const uint16_t microseconds[8]) {
46-
thrusters[FRONT_L].writeMicroseconds(microseconds[FRONT_L]);
47-
thrusters[FRONT_R].writeMicroseconds(microseconds[FRONT_R]);
4846
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]);
5048
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]);
5151
thrusters[HEAVE_FRONT_R].writeMicroseconds(microseconds[HEAVE_FRONT_R]);
52+
thrusters[BACK_R].writeMicroseconds(microseconds[BACK_R]);
5253
thrusters[HEAVE_BACK_R].writeMicroseconds(microseconds[HEAVE_BACK_R]);
53-
thrusters[HEAVE_BACK_L].writeMicroseconds(microseconds[HEAVE_BACK_L]);
5454
}
5555

5656
// updates microseconds array with values from ros
@@ -60,14 +60,14 @@ void commandCb(const auv_msgs::ThrusterMicroseconds &tc) {
6060

6161
// attaches and arms thrusters
6262
void initThrusters() {
63-
thrusters[FRONT_L].attach(FRONT_L_PIN);
64-
thrusters[FRONT_R].attach(FRONT_R_PIN);
6563
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);
6765
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);
6868
thrusters[HEAVE_FRONT_R].attach(HEAVE_FRONT_R_PIN);
69-
thrusters[HEAVE_BACK_L].attach(HEAVE_BACK_L_PIN);
7069
thrusters[HEAVE_BACK_R].attach(HEAVE_BACK_R_PIN);
70+
thrusters[BACK_R].attach(BACK_R_PIN);
7171

7272
updateThrusters(offCommand);
7373
}

0 commit comments

Comments
 (0)