Skip to content
This repository has been archived by the owner on Dec 1, 2020. It is now read-only.

Feature/pm 524 Generalize motor controller #284

Draft
wants to merge 35 commits into
base: develop
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 12 commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
6abd775
Create MotorController abstract class
Roelemans Jul 16, 2020
c8f3af5
Merge branch 'develop' into feature/PM-524-add-odrive-option
Roelemans Aug 5, 2020
f07ebf8
Have Joint.cpp use controller instead of imc
Roelemans Aug 6, 2020
1db4b01
Generalise hardware_builder, hardware_interface and ehtercat master a…
Roelemans Aug 7, 2020
7cf1336
Fix tests #1
Roelemans Aug 7, 2020
9d320e5
Fix tests #2
Roelemans Aug 8, 2020
fffab68
Throw a fatal when a joint has no controller defined and remove runti…
Roelemans Aug 8, 2020
ae33d44
Fix error msg
Roelemans Aug 11, 2020
00e9bad
Fix typos
Roelemans Aug 11, 2020
2e1b2f4
Merge branch 'develop' into feature/PM-524-add-odrive-option
Roelemans Aug 11, 2020
ef553b9
Namechange MotorControllerState to MotorControllerStates
Roelemans Aug 11, 2020
a60801f
Fix clang
Roelemans Aug 11, 2020
087227e
Remove tests untill it works
Roelemans Aug 12, 2020
9d8bc65
Fix build
Roelemans Aug 12, 2020
81423e5
Generalise imc_state change some naming and add docstrings
Roelemans Aug 13, 2020
5e73645
Moved checkState and getErrorStatus from MotorController to MotorCont…
Roelemans Aug 13, 2020
f0c296f
Clang
Roelemans Aug 13, 2020
ea89e8e
Reduce ethercat dependency in naming
Roelemans Aug 14, 2020
03c994a
Merge branch 'develop' into feature/PM-524-add-odrive-option
Roelemans Aug 14, 2020
df36bbf
Mock motor controller and fix bugs
Roelemans Aug 14, 2020
5edecb5
Revert generalise ethercat naming
Roelemans Aug 21, 2020
58fbd2f
Use Ampere instead of IU for torque, and change input/return type of …
Roelemans Aug 21, 2020
855e436
Rename variable in header
Roelemans Aug 21, 2020
e68a574
Return smart pointer instead of reference and minor fixes
Roelemans Aug 24, 2020
0a1c16a
Return smart pointer instead of reference and minor fixes #2
Roelemans Aug 24, 2020
c49c6b3
Merge branch 'develop' into feature/PM-524-add-odrive-option
Roelemans Aug 25, 2020
0fbe358
Create slave_list object
Roelemans Aug 25, 2020
4f66858
Pass a slave list to ethercat master
Roelemans Aug 25, 2020
b48674d
Fix tests
Roelemans Aug 25, 2020
81f0db4
Fix tests
Roelemans Aug 25, 2020
41257c8
Remove initialize from Joint and MotorController
Roelemans Aug 25, 2020
79a93a3
Move hasValidSlaves() to ethercat master
Roelemans Aug 25, 2020
1e55adb
Remove getSlaveIndex from MotorController
Roelemans Aug 25, 2020
ea171c0
Actually use make_shared for shared_ptrs
Roelemans Aug 26, 2020
9b5cc5c
Add docstring
Roelemans Aug 26, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions march_hardware/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ add_library(${PROJECT_NAME}
include/${PROJECT_NAME}/ethercat/sdo_interface.h
include/${PROJECT_NAME}/ethercat/slave.h
include/${PROJECT_NAME}/imotioncube/actuation_mode.h
include/${PROJECT_NAME}/imotioncube/motor_controller.h
include/${PROJECT_NAME}/imotioncube/motor_controller_state.h
Roelemans marked this conversation as resolved.
Show resolved Hide resolved
include/${PROJECT_NAME}/imotioncube/imotioncube.h
include/${PROJECT_NAME}/imotioncube/imotioncube_state.h
include/${PROJECT_NAME}/imotioncube/imotioncube_target_state.h
Expand Down
36 changes: 22 additions & 14 deletions march_hardware/include/march_hardware/imotioncube/imotioncube.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@
#include "march_hardware/ethercat/pdo_types.h"
#include "march_hardware/ethercat/sdo_interface.h"
#include "march_hardware/ethercat/slave.h"
#include "imotioncube_state.h"
#include "motor_controller.h"
#include "motor_controller_state.h"
#include "imotioncube_target_state.h"
#include "march_hardware/encoder/absolute_encoder.h"
#include "march_hardware/encoder/incremental_encoder.h"
Expand All @@ -18,7 +19,7 @@

namespace march
{
class IMotionCube : public Slave
class IMotionCube : public MotorController, public Slave
{
public:
/**
Expand All @@ -36,42 +37,49 @@ class IMotionCube : public Slave
std::unique_ptr<IncrementalEncoder> incremental_encoder, std::string& sw_stream,
ActuationMode actuation_mode);

~IMotionCube() noexcept override = default;
virtual ~IMotionCube() noexcept override = default;

/* Delete copy constructor/assignment since the unique_ptrs cannot be copied */
IMotionCube(const IMotionCube&) = delete;
IMotionCube& operator=(const IMotionCube&) = delete;

virtual double getAngleRadAbsolute();
virtual double getAngleRadIncremental();
virtual double getAngleRadAbsolute() override;
virtual double getAngleRadIncremental() override;
double getAbsoluteRadPerBit() const;
double getIncrementalRadPerBit() const;
int16_t getTorque();
bool getIncrementalMorePrecise() const override;
int16_t getTorque() override;
int32_t getAngleIUAbsolute();
int32_t getAngleIUIncremental();
double getVelocityIUAbsolute();
double getVelocityIUIncremental();
virtual double getVelocityRadAbsolute();
virtual double getVelocityRadIncremental();
virtual double getVelocityRadAbsolute() override;
virtual double getVelocityRadIncremental() override;

uint16_t getStatusWord();
uint16_t getMotionError();
uint16_t getDetailedError();
uint16_t getSecondDetailedError();

ActuationMode getActuationMode() const;
ActuationMode getActuationMode() const override;

virtual float getMotorCurrent();
virtual float getIMCVoltage();
virtual float getMotorVoltage();
virtual float getMotorCurrent() override;
virtual float getMotorControllerVoltage() override;
virtual float getMotorVoltage() override;

bool checkState(std::ostringstream& error_msg, std::string joint_name) override;
MotorControllerStates getStates() override;
void setControlWord(uint16_t control_word);

virtual void actuateRad(double target_rad);
virtual void actuateRad(double target_rad) override;
virtual void actuateTorque(int16_t target_torque);
Roelemans marked this conversation as resolved.
Show resolved Hide resolved

bool initialize(int cycle_time) override;
void goToTargetState(IMotionCubeTargetState target_state);
virtual void goToOperationEnabled();
virtual void goToOperationEnabled() override;

uint16_t getSlaveIndex() const override;
virtual void reset() override;

/** @brief Override comparison operator */
friend bool operator==(const IMotionCube& lhs, const IMotionCube& rhs)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ class IMCState
return "Fault";
case UNKNOWN:
return "Not in a recognized IMC state";
default:
return "Not in a recognized IMC state";
}
}

Expand All @@ -118,30 +120,6 @@ class IMCState
private:
Value value_;
};

struct IMotionCubeState
{
public:
IMotionCubeState() = default;

std::string statusWord;
std::string motionError;
std::string detailedError;
std::string secondDetailedError;
IMCState state;
std::string detailedErrorDescription;
std::string motionErrorDescription;
std::string secondDetailedErrorDescription;

float motorCurrent;
float IMCVoltage;
float motorVoltage;
int absoluteEncoderValue;
int incrementalEncoderValue;
double absoluteVelocity;
double incrementalVelocity;
};

} // namespace march

#endif // MARCH_HARDWARE_IMOTIONCUBE_STATE_H
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;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What if my motor controller does not have either an absolute or incremental encoder?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I thought about this; the incremental/absolute encoders are a characteristic of Joint rather than of the motor controller, so it would make more sense to move such specifications there. That would require me to subclass Joint into different types, which I preferred to avoid, especially since our current three options for motor controllers will probably be connected to both types of encoders. I think such a refactor of the joint class is better postponed to a moment in the future where an encoder is actually connected to something other than a motor controller.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm on second thought, I could move the calculations using both encoders downstream to the motor controller. Then these would simplify to getPosition() and getVelocity(). Downside would be that these calculations would be that this code would probably be duplicate in each different MotorController class, but that might again be resolvable by inheriting from a MultipleEncodersMotorControllers class that implements these methods common for motor controllers with both encoders.

That was a nice spam of hersenspinsels, let me know if it makes any sense and what you think.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Decided that since the 3 motor controllers currently under consideration all have both an incremental and an absolute encoder, this change is not very useful for now. It won't be difficult to implement later on when such a motor controller is actually put to use.

virtual int16_t getTorque() = 0;
virtual MotorControllerStates getStates() = 0;

virtual ActuationMode getActuationMode() const = 0;
virtual uint16_t getSlaveIndex() const = 0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What if a motor controller isn't a slave or doesn't use the master-slave structure.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added a docstring to explain


virtual float getMotorCurrent() = 0;
virtual float getMotorControllerVoltage() = 0;
virtual float getMotorVoltage() = 0;
virtual bool getIncrementalMorePrecise() const = 0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This also seems like a very specific function that should not be inside the motor controller class. When I read this method call I cannot tell what it would do generally on most controllers.

Copy link
Contributor Author

@Roelemans Roelemans Aug 12, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added a docstring with explanation. This method is relevant as long as a motor controller has both an incremental and an absolute encoder.


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.
Show resolved Hide resolved

virtual bool initialize(int cycle_time) = 0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What if my motor controller does not need a cycle time, but it does need something else for initialization. That would require adding more parameters and therefore breaking the contract.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you could alternatively pass something like that to the constructor as well, but I guess that wouldn't be very need since you need it nowhere else. I think I am going to :ostrich: this problem since it is highly dependent on how exactly the startup of another motor controller would work, which is a bit difficult to predict. I will see if I get useful enough insight from the ODrive and the Ingenia to make general statements about this. Otherwise, I think I will leave it up to future generations to redesign this a bit.

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 MotorControllerStates
{
public:
MotorControllerStates() = 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.
Show resolved Hide resolved
};

} // namespace march

#endif // MARCH_HARDWARE_IMOTIONCUBE_STATE_H
36 changes: 15 additions & 21 deletions march_hardware/include/march_hardware/joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <march_hardware/imotioncube/imotioncube.h>
#include <march_hardware/power/power_distribution_board.h>
#include <march_hardware/temperature/temperature_ges.h>
#include <march_hardware/imotioncube/imotioncube_state.h>
#include <march_hardware/imotioncube/motor_controller_state.h>

namespace march
{
Expand All @@ -26,12 +26,12 @@ class Joint
/**
* Initializes a Joint with motor controller and without temperature slave.
*/
Joint(std::string name, int net_number, bool allow_actuation, std::unique_ptr<IMotionCube> imc);
Joint(std::string name, int net_number, bool allow_actuation, std::unique_ptr<MotorController> controller);

/**
* Initializes a Joint with motor controller and temperature slave.
*/
Joint(std::string name, int net_number, bool allow_actuation, std::unique_ptr<IMotionCube> imc,
Joint(std::string name, int net_number, bool allow_actuation, std::unique_ptr<MotorController> controller,
std::unique_ptr<TemperatureGES> temperature_ges);

virtual ~Joint() noexcept = default;
Expand All @@ -40,7 +40,7 @@ class Joint
Joint(const Joint&) = delete;
Joint& operator=(const Joint&) = delete;

void resetIMotionCube();
void resetMotorController();

/* Delete move assignment since string cannot be move assigned */
Joint(Joint&&) = default;
Expand All @@ -64,16 +64,17 @@ class Joint
double getVelocityIUAbsolute();
double getVelocityIUIncremental();
float getTemperature();
IMotionCubeState getIMotionCubeState();
MotorControllerStates getMotorControllerStates();
virtual bool checkMotorControllerState(std::ostringstream& error_stream);
Olavhaasie marked this conversation as resolved.
Show resolved Hide resolved

std::string getName() const;
int getTemperatureGESSlaveIndex() const;
int getIMotionCubeSlaveIndex() const;
int getMotorControllerSlaveIndex() const;
int getNetNumber() const;

ActuationMode getActuationMode() const;

bool hasIMotionCube() const;
bool hasMotorController() const;
Roelemans marked this conversation as resolved.
Show resolved Hide resolved
bool hasTemperatureGES() const;
bool canActuate() const;
bool receivedDataUpdate();
Expand All @@ -82,7 +83,10 @@ class Joint
/** @brief Override comparison operator */
friend bool operator==(const Joint& lhs, const Joint& rhs)
{
return lhs.name_ == rhs.name_ && ((lhs.imc_ && rhs.imc_ && *lhs.imc_ == *rhs.imc_) || (!lhs.imc_ && !rhs.imc_)) &&
return lhs.name_ == rhs.name_ &&
((lhs.controller_ && rhs.controller_ &&
lhs.controller_->getSlaveIndex() == rhs.controller_->getSlaveIndex()) ||
(!lhs.controller_ && !rhs.controller_)) &&
((lhs.temperature_ges_ && rhs.temperature_ges_ && *lhs.temperature_ges_ == *rhs.temperature_ges_) ||
(!lhs.temperature_ges_ && !rhs.temperature_ges_)) &&
lhs.allow_actuation_ == rhs.allow_actuation_ &&
Expand All @@ -99,17 +103,7 @@ class Joint
os << "name: " << joint.name_ << ", "
<< "ActuationMode: " << joint.getActuationMode().toString() << ", "
<< "allowActuation: " << joint.allow_actuation_ << ", "
<< "imotioncube: ";
if (joint.imc_)
{
os << *joint.imc_;
}
else
{
os << "none";
}

os << ", temperatureges: ";
<< "imotioncube slave index: " << joint.getMotorControllerSlaveIndex() << ", temperatureges: ";
if (joint.temperature_ges_)
{
os << *joint.temperature_ges_;
Expand All @@ -126,7 +120,7 @@ class Joint
const std::string name_;
const int net_number_;
bool allow_actuation_ = false;
float previous_imc_volt_ = 0.0;
float previous_controller_volt_ = 0.0;
float previous_motor_current_ = 0.0;
float previous_motor_volt_ = 0.0;
double previous_absolute_position_ = 0.0;
Expand All @@ -139,7 +133,7 @@ class Joint
double absolute_position_ = 0.0;
double velocity_ = 0.0;

std::unique_ptr<IMotionCube> imc_ = nullptr;
std::unique_ptr<MotorController> controller_ = nullptr;
Olavhaasie marked this conversation as resolved.
Show resolved Hide resolved
std::unique_ptr<TemperatureGES> temperature_ges_ = nullptr;
};

Expand Down
4 changes: 2 additions & 2 deletions march_hardware/src/ethercat/ethercat_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ bool EthercatMaster::ethercatSlaveInitiation(std::vector<Joint>& joints)

for (Joint& joint : joints)
{
if (joint.hasIMotionCube())
if (joint.getMotorControllerSlaveIndex() > -1)
Roelemans marked this conversation as resolved.
Show resolved Hide resolved
{
ec_slave[joint.getIMotionCubeSlaveIndex()].PO2SOconfig = setSlaveWatchdogTimer;
ec_slave[joint.getMotorControllerSlaveIndex()].PO2SOconfig = setSlaveWatchdogTimer;
}
reset |= joint.initialize(this->cycle_time_ms_);
}
Expand Down
Loading