Skip to content

Commit f330f8b

Browse files
committed
Issue #14-2: Minor code fixes. Deleting unused variables. Updating tests
1 parent 87aa7c9 commit f330f8b

File tree

6 files changed

+6
-30
lines changed

6 files changed

+6
-30
lines changed

src/kpi_rover_ecu/include/PIDRegulator.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,4 +19,4 @@ class PIDRegulator {
1919
const float kIntegralLimit = 26500;
2020
};
2121

22-
#endif
22+
#endif

src/kpi_rover_ecu/include/motor.h

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -6,15 +6,13 @@
66

77
#include "PIDRegulator.h"
88

9-
#define SECONDSTOMINUTE 60
10-
#define MILISECONDSTOSECOND 1000
11-
129
class Motor {
1310
public:
14-
static constexpr int kMinRpm = 8000;
1511
static constexpr int kMaxRpm = 26500;
1612
static constexpr int kLoopTicks = 821;
1713
static constexpr int kSpeedIndexMultipler = 100;
14+
static constexpr int kSecondsMinute = 60;
15+
static constexpr int kMiliSecondsSeconds = 1000;
1816

1917
Motor(int assigned_number, bool is_inverted, std::array<float, 3> _coeficients);
2018
int MotorGo(int newRPM);
@@ -23,7 +21,6 @@ class Motor {
2321

2422
private:
2523
int MotorSet(int inputRPM);
26-
static constexpr int kBrakeTime = 100000; // 100 ms
2724

2825
PIDRegulator pidRegulator_;
2926
int setpointRpm_;

src/kpi_rover_ecu/include/motorConfig.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,4 +19,4 @@ class MotorConfig {
1919
std::array<float, 3> pidCoefs_ = {};
2020
};
2121

22-
#endif // MOTOR_CONFIG_H
22+
#endif // MOTOR_CONFIG_H

src/kpi_rover_ecu/src/PIDRegulator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,4 +28,4 @@ int PIDRegulator::Run(float kError, float kTimeDt) {
2828
previousError_ = kError;
2929

3030
return static_cast<int>(kPTerm + kITerm + kDTerm);
31-
}
31+
}

src/kpi_rover_ecu/src/motor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ int Motor::GetEncoderCounter() {
7272

7373
const float kRevolutions = static_cast<float>(pid_encoder_ticks) / static_cast<float>(kLoopTicks);
7474
const float kInputPoint =
75-
static_cast<float>(std::round((kRevolutions * SECONDSTOMINUTE * MILISECONDSTOSECOND) / kTimeDt)) *
75+
static_cast<float>(std::round((kRevolutions * kSecondsMinute * kMiliSecondsSeconds) / kTimeDt)) *
7676
kSpeedIndexMultipler;
7777
actualRpm_ = static_cast<int>(kInputPoint);
7878
const float kError = static_cast<float>(setpointRpm_) - kInputPoint;

src/kpi_rover_ecu/tests/test_motor.cpp

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -44,16 +44,6 @@ TEST_F(MotorTest, MotorGoCallsRcMotorSet) {
4444
EXPECT_EQ(0, result) << "MotorGo should return success";
4545
}
4646

47-
// Test MotorGo with minimum RPM
48-
TEST_F(MotorTest, MotorGoMinRPM) {
49-
EXPECT_CALL(GetMockRCMotor(), set(0, ::testing::_)).WillOnce(::testing::Return(0));
50-
51-
motor = new Motor(0, false, {1.5f, 0.056f, 1.5f});
52-
int result = motor->MotorGo(Motor::kMinRpm);
53-
54-
EXPECT_EQ(0, result);
55-
}
56-
5747
// Test MotorGo with inverted motor direction
5848
TEST_F(MotorTest, MotorGoInverted) {
5949
// For inverted motor, the duty cycle should be negative
@@ -65,17 +55,6 @@ TEST_F(MotorTest, MotorGoInverted) {
6555
EXPECT_EQ(0, result);
6656
}
6757

68-
// Test MotorGo with RPM below minimum
69-
TEST_F(MotorTest, MotorGoBelowMinRPM) {
70-
// Verify behavior with RPM below minimum (should set to MIN_RPM or handle specially)
71-
EXPECT_CALL(GetMockRCMotor(), set(0, ::testing::_)).WillOnce(::testing::Return(0));
72-
73-
motor = new Motor(0, false, {1.5f, 0.056f, 1.5f});
74-
int result = motor->MotorGo(Motor::kMinRpm - 1);
75-
76-
EXPECT_EQ(0, result);
77-
}
78-
7958
// Test MotorGo with RPM above maximum
8059
TEST_F(MotorTest, MotorGoAboveMaxRPM) {
8160
// Verify behavior with RPM above maximum (should clamp to MAX_RPM)

0 commit comments

Comments
 (0)