Skip to content

Commit dfc7c63

Browse files
committed
Issue #14-2: Fixing code style
1 parent 1ebdcad commit dfc7c63

File tree

5 files changed

+18
-17
lines changed

5 files changed

+18
-17
lines changed

src/kpi_rover_ecu/include/PIDRegulator.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,11 @@
33

44
#pragma once
55

6-
#include <chrono>
76
#include <array>
7+
#include <chrono>
88

99
#define SECONDSTOMINUTE 60
1010
#define MILISECONDSTOSECOND 1000
11-
#define SPEEDINDEXMULTIPLIER 100
1211

1312
class PIDRegulator {
1413
public:
@@ -22,8 +21,9 @@ class PIDRegulator {
2221
float kd_;
2322
int previousError_ = 0;
2423
int integral_ = 0;
25-
const int integralLimit_ = 26500;
26-
const int outputLimit_ = 26500;
24+
const int kintegralLimit_ = 26500;
25+
const int koutputLimit_ = 26500;
26+
const int kSpeedIndexMultipler_ = 100;
2727
int loopsTicks_;
2828
int maxRPM_;
2929

src/kpi_rover_ecu/include/motor.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
#define MOTOR_H
33

44
#include <array>
5+
56
#include "PIDRegulator.h"
67

78
class Motor {

src/kpi_rover_ecu/src/PIDRegulator.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -19,27 +19,27 @@ void PIDRegulator::Init(std::array<float, 3> _coeficients, int _loopsTicks, int
1919

2020
int PIDRegulator::Run(int setpoint, int ticks_value) {
2121
const auto kCurrentTimePoint = std::chrono::high_resolution_clock::now();
22-
const std::chrono::duration<double, std::milli> kElapsedMilliseconds =
23-
kCurrentTimePoint - lastTimePoint_;
22+
const std::chrono::duration<double, std::milli> kElapsedMilliseconds = kCurrentTimePoint - lastTimePoint_;
2423
lastTimePoint_ = kCurrentTimePoint;
2524
const auto kTimeDt = static_cast<float>(kElapsedMilliseconds.count());
2625

2726
const float kRevolutions = static_cast<float>(ticks_value) / static_cast<float>(loopsTicks_);
2827

29-
const float kInputPoint = static_cast<float>(
30-
std::round((kRevolutions * SECONDSTOMINUTE * MILISECONDSTOSECOND) / kTimeDt)) *
31-
SPEEDINDEXMULTIPLIER;
32-
const float kError = static_cast<float>(setpoint) - kInputPoint; // get rid of abs() !!!
28+
const float kInputPoint =
29+
static_cast<float>(std::round((kRevolutions * SECONDSTOMINUTE * MILISECONDSTOSECOND) / kTimeDt)) *
30+
kSpeedIndexMultipler_;
31+
32+
const float kError = static_cast<float>(setpoint) - kInputPoint;
3333
std::cout << "set point " << setpoint << " current point " << kInputPoint << " error " << kError << '\n';
3434

3535
const float kPTerm = kp_ * kError;
3636

3737
integral_ += kError * kTimeDt;
38-
if (integral_ > integralLimit_) {
39-
integral_ = integralLimit_;
38+
if (integral_ > kintegralLimit_) {
39+
integral_ = kintegralLimit_;
4040
}
41-
if (integral_ < -integralLimit_) {
42-
integral_ = -integralLimit_;
41+
if (integral_ < -kintegralLimit_) {
42+
integral_ = -kintegralLimit_;
4343
}
4444

4545
const float kITerm = ki_ * integral_;

src/kpi_rover_ecu/src/main.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ int main(int argc, char* argv[]) {
5858
MotorConfig(3, false, {1.5, 0.056, 1.5}),
5959
MotorConfig(4, false, {1.5, 0.056, 1.5}),
6060
MotorConfig(1, true, {1.5, 0.056, 1.5}),
61-
MotorConfig(2, true, {1.5, 0.056, 1.5})
61+
MotorConfig(2, true, {1.5, 0.056, 1.5}),
6262
};
6363

6464
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
@@ -1,11 +1,12 @@
11
#include "motor.h"
2-
#include "PIDRegulator.h"
32

43
#include <rc/encoder.h>
54
#include <rc/motor.h>
65

76
#include <iostream>
87

8+
#include "PIDRegulator.h"
9+
910
Motor::Motor(int assigned_number, bool is_inverted, std::array<float, 3> _coeficients)
1011
: motorNumber_(assigned_number), inverted_(is_inverted), currentDutyCycle_(0), currentRpm_(0) {
1112
pidRegulator_.Init(_coeficients, kLoopTicks, kMaxRpm);
@@ -22,7 +23,6 @@ int Motor::MotorGo(int newRPM) {
2223
newRPM = -kMaxRpm;
2324
}
2425

25-
2626
if (MotorSet(newRPM) == -1) {
2727
return -1;
2828
}

0 commit comments

Comments
 (0)