-
Notifications
You must be signed in to change notification settings - Fork 3
Feature/pm 524 Generalize motor controller #284
base: develop
Are you sure you want to change the base?
Changes from 10 commits
6abd775
c8f3af5
f07ebf8
1db4b01
7cf1336
9d320e5
fffab68
ae33d44
00e9bad
2e1b2f4
ef553b9
a60801f
087227e
9d8bc65
81423e5
5e73645
f0c296f
ea89e8e
03c994a
df36bbf
5edecb5
58fbd2f
855e436
e68a574
0a1c16a
c49c6b3
0fbe358
4f66858
b48674d
81f0db4
41257c8
79a93a3
1e55adb
ea171c0
9b5cc5c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
// Copyright 2019 Project March. | ||
|
||
#include "actuation_mode.h" | ||
#include "motor_controller_state.h" | ||
#include <string> | ||
|
||
namespace march | ||
{ | ||
class MotorController | ||
{ | ||
public: | ||
virtual double getAngleRadAbsolute() = 0; | ||
virtual double getAngleRadIncremental() = 0; | ||
virtual double getVelocityRadAbsolute() = 0; | ||
virtual double getVelocityRadIncremental() = 0; | ||
|
||
virtual int16_t getTorque() = 0; | ||
virtual MotorControllerState getStates() = 0; | ||
|
||
virtual ActuationMode getActuationMode() const = 0; | ||
virtual uint16_t getSlaveIndex() const = 0; | ||
|
||
|
||
virtual float getMotorCurrent() = 0; | ||
virtual float getMotorControllerVoltage() = 0; | ||
virtual float getMotorVoltage() = 0; | ||
virtual bool getIncrementalMorePrecise() const = 0; | ||
|
||
|
||
virtual void actuateRad(double target_rad) = 0; | ||
virtual void actuateTorque(int16_t target_torque) = 0; | ||
|
||
virtual void goToOperationEnabled() = 0; | ||
Olavhaasie marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
virtual bool initialize(int cycle_time) = 0; | ||
|
||
virtual void reset() = 0; | ||
virtual bool checkState(std::ostringstream& error_msg, std::string joint_name) = 0; | ||
|
||
virtual ~MotorController() noexcept = default; | ||
}; | ||
|
||
} // namespace march |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,35 @@ | ||
// Copyright 2019 Project March. | ||
#ifndef MARCH_HARDWARE_MOTOR_CONTROLLER_STATE_H | ||
#define MARCH_HARDWARE_MOTOR_CONTROLLER_STATE_H | ||
|
||
#include <string> | ||
#include "imotioncube_state.h" | ||
|
||
namespace march | ||
{ | ||
struct MotorControllerState | ||
{ | ||
public: | ||
MotorControllerState() = default; | ||
|
||
float motorCurrent; | ||
float controllerVoltage; | ||
float motorVoltage; | ||
int absoluteEncoderValue; | ||
int incrementalEncoderValue; | ||
double absoluteVelocity; | ||
double incrementalVelocity; | ||
|
||
std::string statusWord; | ||
std::string motionError; | ||
std::string detailedError; | ||
std::string secondDetailedError; | ||
IMCState state; | ||
std::string detailedErrorDescription; | ||
std::string motionErrorDescription; | ||
std::string secondDetailedErrorDescription; | ||
Roelemans marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
}; | ||
|
||
} // namespace march | ||
|
||
#endif // MARCH_HARDWARE_IMOTIONCUBE_STATE_H |
Uh oh!
There was an error while loading. Please reload this page.