Skip to content

Commit 4e73847

Browse files
taketook34AksonovSergei
authored andcommitted
Issue #11: Changing Motor and MotorController function names on correct
1 parent 10f3e43 commit 4e73847

File tree

5 files changed

+6
-6
lines changed

5 files changed

+6
-6
lines changed

src/kpi_rover_ecu/include/motor.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ class Motor {
1515
Motor(int assignedNumber, bool isInverted);
1616
int MotorGo(int newRPM);
1717
int MotorStop() const ;
18-
int GetRPM() const ;
18+
int GetEncoderCounter() const ;
1919

2020
private:
2121
int motorNumber_;

src/kpi_rover_ecu/include/motorsController.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ class MotorController {
1515
int SetMotorRPM(int channel, int newRPM);
1616
int StopMotor(int channel);
1717

18-
int GetMotorRPM(int channel);
18+
int GetEncoderCounter(int channel);
1919
int GetMotorsNumber();
2020
void Destroy();
2121

src/kpi_rover_ecu/src/motor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ int Motor::MotorStop() const {
3333
return 0;
3434
}
3535

36-
int Motor::GetRPM() const {
36+
int Motor::GetEncoderCounter() const {
3737
const int kEncoderTicks = rc_encoder_read(motorNumber_);
3838
rc_encoder_write(motorNumber_, 0);
3939
return kEncoderTicks;

src/kpi_rover_ecu/src/motorsController.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ void MotorController::Destroy() {
8080
rc_encoder_cleanup();
8181
}
8282

83-
int MotorController::GetMotorRPM(int channel) { return motors_[channel].GetRPM(); }
83+
int MotorController::GetEncoderCounter(int channel) { return motors_[channel].GetEncoderCounter(); }
8484

8585
int MotorController::GetMotorsNumber() { return motor_number_; }
8686

src/kpi_rover_ecu/src/protocolHandler.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ vector<uint8_t> ProtocolHanlder::HandleGetEncoder(vector<uint8_t> message) {
6969
vector<uint8_t> ret_val;
7070
std::cout << "[COMMAND] get motor " << static_cast<int>(kMotorId) << " encoder " << '\n';
7171

72-
const int32_t kMotorRpm = main_controller_->GetMotorRPM(kMotorId);
72+
const int32_t kMotorRpm = main_controller_->GetEncoderCounter(kMotorId);
7373

7474
ret_val.push_back(ID_GET_ENCODER);
7575

@@ -85,7 +85,7 @@ vector<uint8_t> ProtocolHanlder::HandleGetAllEncoders(vector<uint8_t> message) c
8585
ret_val.push_back(ID_GET_ALL_ENCODERS);
8686

8787
for (int i = 0; i < main_controller_->GetMotorsNumber(); i++) {
88-
int32_t encoder_rpm = static_cast<int32_t>(htonl(main_controller_->GetMotorRPM(i)));
88+
int32_t encoder_rpm = static_cast<int32_t>(htonl(main_controller_->GetEncoderCounter(i)));
8989
ret_val.insert(ret_val.end(), reinterpret_cast<uint8_t*>(&encoder_rpm),
9090
reinterpret_cast<uint8_t*>(&encoder_rpm) + sizeof(int32_t));
9191
}

0 commit comments

Comments
 (0)