Skip to content

Commit 6006c13

Browse files
committed
Issue #14. Fixing some errors after rebasing
1 parent b87a171 commit 6006c13

File tree

4 files changed

+10
-8
lines changed

4 files changed

+10
-8
lines changed

src/kpi_rover_ecu/include/motor.h

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,16 @@
99

1010
#include "PIDRegulator.h"
1111

12-
#define MIN_RPM 8000
13-
#define MAX_RPM 26500
14-
#define BRAKE_TIME 100000 // 100 ms
15-
#define LOOP_TICKS 821
1612

1713
using namespace std;
1814

1915
class Motor {
2016
public:
17+
static constexpr int kMinRpm = 8000;
18+
static constexpr int kMaxRpm = 26500;
19+
static constexpr int kLoopTicks = 821;
20+
21+
2122
Motor(int assignedNumber, bool isInverted, array<float, 3> _coeficients);
2223
int MotorGo(int newRPM);
2324
int MotorStop();

src/kpi_rover_ecu/src/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ add_library(kpi_rover_ecu_core STATIC
66
TCPTransport.cpp
77
motorConfig.cpp
88
messageQueue.cpp
9+
PIDRegulator.cpp
910
)
1011

1112
# Include public headers

src/kpi_rover_ecu/src/main.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,8 @@ int main(int argc, char* argv[]) {
5353
// sem_init(&stopProgramSem, 0, 0);
5454
// 4.42, 0.162
5555
MotorController motors_processor;
56-
const uint8_t kMotorNumber = MOTORS_NUMBER;
57-
MotorConfig shassis_array[] = {MotorConfig(1, false, {1.5, 0.056, 1.5}), MotorConfig(2, false, {1.5, 0.056, 1.5}),
56+
const uint8_t kMotorNumber = 4;
57+
const std::vector<MotorConfig> kShassisVector = {MotorConfig(1, false, {1.5, 0.056, 1.5}), MotorConfig(2, false, {1.5, 0.056, 1.5}),
5858
MotorConfig(3, true, {1.5, 0.056, 1.5}), MotorConfig(4, true, {1.5, 0.056, 1.5})};
5959

6060
motors_processor.Init(kShassisVector, kMotorNumber);

src/kpi_rover_ecu/src/motor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
Motor::Motor(int assignedNumber, bool isInverted, array<float, 3> _coeficients)
44
: motorNumber_(assignedNumber), inverted_(isInverted), currentDutyCycle_(0), currentRPM_(0) {
5-
pidRegulator_.Init(_coeficients, LOOP_TICKS, MAX_RPM);
5+
pidRegulator_.Init(_coeficients, kLoopTicks, kMaxRpm);
66
}
77

88
int Motor::MotorGo(int newRPM) {
@@ -34,7 +34,7 @@ int Motor::MotorStop() {
3434
return -1;
3535
}
3636

37-
rc_usleep(BRAKE_TIME);
37+
rc_usleep(kBrakeTime);
3838

3939
if (rc_motor_free_spin(motorNumber_) != 0) {
4040
std::cout << "[ERROR][RC] rc_motor_free_spin" << '\n';

0 commit comments

Comments
 (0)