Skip to content

Commit

Permalink
refactor: Separate CAN from protocol-independent classes and add driv…
Browse files Browse the repository at this point in the history
…er as abstraction
  • Loading branch information
2b-t committed Feb 24, 2024
1 parent 12dc221 commit 9ee21fb
Show file tree
Hide file tree
Showing 34 changed files with 735 additions and 549 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ add_library(myactuator_rmd SHARED
src/can/utilities.cpp
src/protocol/requests.cpp
src/protocol/responses.cpp
src/actuator.cpp
src/actuator_interface.cpp
)
target_include_directories(myactuator_rmd PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
Expand Down
6 changes: 4 additions & 2 deletions ReadMe.md
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,8 @@ A minimal example for the `main.cpp` can be found below:


int main() {
myactuator_rmd::Actuator actuator {"can0", 1};
myactuator_rmd::CanDriver driver {"can0"};
myactuator_rmd::Actuator actuator {driver, 1};
std::cout << actuator.getVersionDate() << std::endl;
return EXIT_SUCCESS;
}
Expand All @@ -113,7 +114,8 @@ $ python3
Python 3.10.6 (main, Mar 10 2023, 10:55:28) [GCC 11.3.0] on linux
Type "help", "copyright", "credits" or "license" for more information.
>>> import myactuator_rmd_py as rmd
>>> actuator = rmd.Actuator("can0", 1)
>>> driver = rmd.CanDriver("can0")
>>> actuator = rmd.Actuator(driver, 1)
>>> actuator.getVersionDate()
2023020601
>>> actuator.sendPositionAbsoluteSetpoint(180.0, 500.0)
Expand Down
84 changes: 44 additions & 40 deletions bindings/myactuator_rmd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <pybind11/stl.h>

#include "myactuator_rmd/actuator_state/acceleration_type.hpp"
#include "myactuator_rmd/actuator_state/baud_rate.hpp"
#include "myactuator_rmd/actuator_state/can_baud_rate.hpp"
#include "myactuator_rmd/actuator_state/control_mode.hpp"
#include "myactuator_rmd/actuator_state/error_code.hpp"
#include "myactuator_rmd/actuator_state/feedback.hpp"
Expand All @@ -27,8 +27,10 @@
#include "myactuator_rmd/can/exceptions.hpp"
#include "myactuator_rmd/can/frame.hpp"
#include "myactuator_rmd/can/node.hpp"
#include "myactuator_rmd/driver/can_driver.hpp"
#include "myactuator_rmd/driver/driver.hpp"
#include "myactuator_rmd/actuator_constants.hpp"
#include "myactuator_rmd/actuator.hpp"
#include "myactuator_rmd/actuator_interface.hpp"
#include "myactuator_rmd/exceptions.hpp"
#include "myactuator_rmd/io.hpp"

Expand Down Expand Up @@ -63,41 +65,43 @@ namespace myactuator_rmd {
PYBIND11_MODULE(myactuator_rmd_py, m) {

m.doc() = "MyActuator RMD main module";
pybind11::class_<myactuator_rmd::Actuator>(m, "Actuator")
.def(pybind11::init<std::string const&, std::uint32_t>())
.def("getAcceleration", &myactuator_rmd::Actuator::getAcceleration)
.def("getCanId", &myactuator_rmd::Actuator::getCanId)
.def("getControllerGains", &myactuator_rmd::Actuator::getControllerGains)
.def("getControlMode", &myactuator_rmd::Actuator::getControlMode)
.def("getMotorModel", &myactuator_rmd::Actuator::getMotorModel)
.def("getMotorPower", &myactuator_rmd::Actuator::getMotorPower)
.def("getMotorStatus1", &myactuator_rmd::Actuator::getMotorStatus1)
.def("getMotorStatus2", &myactuator_rmd::Actuator::getMotorStatus2)
.def("getMotorStatus3", &myactuator_rmd::Actuator::getMotorStatus3)
.def("getMultiTurnAngle", &myactuator_rmd::Actuator::getMultiTurnAngle)
.def("getMultiTurnEncoderPosition", &myactuator_rmd::Actuator::getMultiTurnEncoderPosition)
.def("getMultiTurnEncoderOriginalPosition", &myactuator_rmd::Actuator::getMultiTurnEncoderOriginalPosition)
.def("getMultiTurnEncoderZeroOffset", &myactuator_rmd::Actuator::getMultiTurnEncoderZeroOffset)
.def("getRuntime", &myactuator_rmd::Actuator::getRuntime)
.def("getSingleTurnAngle", &myactuator_rmd::Actuator::getSingleTurnAngle)
.def("getSingleTurnEncoderPosition", &myactuator_rmd::Actuator::getSingleTurnEncoderPosition)
.def("getVersionDate", &myactuator_rmd::Actuator::getVersionDate)
.def("lockBrake", &myactuator_rmd::Actuator::lockBrake)
.def("releaseBrake", &myactuator_rmd::Actuator::releaseBrake)
.def("reset", &myactuator_rmd::Actuator::reset)
.def("sendCurrentSetpoint", &myactuator_rmd::Actuator::sendCurrentSetpoint)
.def("sendPositionAbsoluteSetpoint", &myactuator_rmd::Actuator::sendPositionAbsoluteSetpoint)
.def("sendTorqueSetpoint", &myactuator_rmd::Actuator::sendTorqueSetpoint)
.def("sendVelocitySetpoint", &myactuator_rmd::Actuator::sendVelocitySetpoint)
.def("setAcceleration", &myactuator_rmd::Actuator::setAcceleration)
.def("setBaudRate", &myactuator_rmd::Actuator::setBaudRate)
.def("setCanId", &myactuator_rmd::Actuator::setCanId)
.def("setControllerGains", &myactuator_rmd::Actuator::setControllerGains)
.def("setCurrentPositionAsEncoderZero", &myactuator_rmd::Actuator::setCurrentPositionAsEncoderZero)
.def("setEncoderZero", &myactuator_rmd::Actuator::setEncoderZero)
.def("setTimeout", &myactuator_rmd::Actuator::setTimeout)
.def("shutdownMotor", &myactuator_rmd::Actuator::shutdownMotor)
.def("stopMotor", &myactuator_rmd::Actuator::stopMotor);
pybind11::class_<myactuator_rmd::CanDriver>(m, "CanDriver")
.def(pybind11::init<std::string const&>());
pybind11::class_<myactuator_rmd::ActuatorInterface>(m, "ActuatorInterface")
.def(pybind11::init<myactuator_rmd::Driver&, std::uint32_t>())
.def("getAcceleration", &myactuator_rmd::ActuatorInterface::getAcceleration)
.def("getCanId", &myactuator_rmd::ActuatorInterface::getCanId)
.def("getControllerGains", &myactuator_rmd::ActuatorInterface::getControllerGains)
.def("getControlMode", &myactuator_rmd::ActuatorInterface::getControlMode)
.def("getMotorModel", &myactuator_rmd::ActuatorInterface::getMotorModel)
.def("getMotorPower", &myactuator_rmd::ActuatorInterface::getMotorPower)
.def("getMotorStatus1", &myactuator_rmd::ActuatorInterface::getMotorStatus1)
.def("getMotorStatus2", &myactuator_rmd::ActuatorInterface::getMotorStatus2)
.def("getMotorStatus3", &myactuator_rmd::ActuatorInterface::getMotorStatus3)
.def("getMultiTurnAngle", &myactuator_rmd::ActuatorInterface::getMultiTurnAngle)
.def("getMultiTurnEncoderPosition", &myactuator_rmd::ActuatorInterface::getMultiTurnEncoderPosition)
.def("getMultiTurnEncoderOriginalPosition", &myactuator_rmd::ActuatorInterface::getMultiTurnEncoderOriginalPosition)
.def("getMultiTurnEncoderZeroOffset", &myactuator_rmd::ActuatorInterface::getMultiTurnEncoderZeroOffset)
.def("getRuntime", &myactuator_rmd::ActuatorInterface::getRuntime)
.def("getSingleTurnAngle", &myactuator_rmd::ActuatorInterface::getSingleTurnAngle)
.def("getSingleTurnEncoderPosition", &myactuator_rmd::ActuatorInterface::getSingleTurnEncoderPosition)
.def("getVersionDate", &myactuator_rmd::ActuatorInterface::getVersionDate)
.def("lockBrake", &myactuator_rmd::ActuatorInterface::lockBrake)
.def("releaseBrake", &myactuator_rmd::ActuatorInterface::releaseBrake)
.def("reset", &myactuator_rmd::ActuatorInterface::reset)
.def("sendCurrentSetpoint", &myactuator_rmd::ActuatorInterface::sendCurrentSetpoint)
.def("sendPositionAbsoluteSetpoint", &myactuator_rmd::ActuatorInterface::sendPositionAbsoluteSetpoint)
.def("sendTorqueSetpoint", &myactuator_rmd::ActuatorInterface::sendTorqueSetpoint)
.def("sendVelocitySetpoint", &myactuator_rmd::ActuatorInterface::sendVelocitySetpoint)
.def("setAcceleration", &myactuator_rmd::ActuatorInterface::setAcceleration)
.def("setCanBaudRate", &myactuator_rmd::ActuatorInterface::setCanBaudRate)
.def("setCanId", &myactuator_rmd::ActuatorInterface::setCanId)
.def("setControllerGains", &myactuator_rmd::ActuatorInterface::setControllerGains)
.def("setCurrentPositionAsEncoderZero", &myactuator_rmd::ActuatorInterface::setCurrentPositionAsEncoderZero)
.def("setEncoderZero", &myactuator_rmd::ActuatorInterface::setEncoderZero)
.def("setTimeout", &myactuator_rmd::ActuatorInterface::setTimeout)
.def("shutdownMotor", &myactuator_rmd::ActuatorInterface::shutdownMotor)
.def("stopMotor", &myactuator_rmd::ActuatorInterface::stopMotor);
pybind11::register_exception<myactuator_rmd::Exception>(m, "ActuatorException");
pybind11::register_exception<myactuator_rmd::ProtocolException>(m, "ProtocolException");
pybind11::register_exception<myactuator_rmd::ValueRangeException>(m, "ValueRangeException");
Expand All @@ -108,9 +112,9 @@ PYBIND11_MODULE(myactuator_rmd_py, m) {
.value("POSITION_PLANNING_DECELERATION", myactuator_rmd::AccelerationType::POSITION_PLANNING_DECELERATION)
.value("VELOCITY_PLANNING_ACCELERATION", myactuator_rmd::AccelerationType::VELOCITY_PLANNING_ACCELERATION)
.value("VELOCITY_PLANNING_DECELERATION", myactuator_rmd::AccelerationType::VELOCITY_PLANNING_DECELERATION);
pybind11::enum_<myactuator_rmd::BaudRate>(m_actuator_state, "BaudRate")
.value("KBPS500", myactuator_rmd::BaudRate::KBPS500)
.value("MBPS1", myactuator_rmd::BaudRate::MBPS1);
pybind11::enum_<myactuator_rmd::CanBaudRate>(m_actuator_state, "CanBaudRate")
.value("KBPS500", myactuator_rmd::CanBaudRate::KBPS500)
.value("MBPS1", myactuator_rmd::CanBaudRate::MBPS1);
pybind11::enum_<myactuator_rmd::ControlMode>(m_actuator_state, "ControlMode")
.value("NONE", myactuator_rmd::ControlMode::NONE)
.value("CURRENT", myactuator_rmd::ControlMode::CURRENT)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,54 +1,53 @@
/**
* \file actuator.hpp
* \file actuator_interface.hpp
* \mainpage
* Contains the main driver
* Contains the interface to a single actuator
* \author
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__ACTUATOR
#define MYACTUATOR_RMD__ACTUATOR
#ifndef MYACTUATOR_RMD__ACTUATOR_INTERFACE
#define MYACTUATOR_RMD__ACTUATOR_INTERFACE
#pragma once

#include <chrono>
#include <cstdint>
#include <string>

#include "myactuator_rmd/actuator_state/acceleration_type.hpp"
#include "myactuator_rmd/actuator_state/baud_rate.hpp"
#include "myactuator_rmd/actuator_state/can_baud_rate.hpp"
#include "myactuator_rmd/actuator_state/control_mode.hpp"
#include "myactuator_rmd/actuator_state/feedback.hpp"
#include "myactuator_rmd/actuator_state/gains.hpp"
#include "myactuator_rmd/actuator_state/motor_status_1.hpp"
#include "myactuator_rmd/actuator_state/motor_status_2.hpp"
#include "myactuator_rmd/actuator_state/motor_status_3.hpp"
#include "myactuator_rmd/protocol/address_offset.hpp"
#include "myactuator_rmd/protocol/node.hpp"
#include "myactuator_rmd/driver/driver.hpp"


namespace myactuator_rmd {

/**\class Actuator
/**\class ActuatorInterface
* \brief
* Actuator for commanding the MyActuator RMD actuator series
*/
class Actuator: protected Node<AddressOffset::request,AddressOffset::response> {
class ActuatorInterface {
public:
/**\fn Actuator
/**\fn ActuatorInterface
* \brief
* Class constructor
*
* \param[in] ifname
* The name of the network interface that should communicated over
* \param[in] driver
* The driver communicating over the network interface
* \param[in] actuator_id
* The actuator id [1, 32]
*/
Actuator(std::string const& ifname, std::uint32_t const actuator_id);
Actuator() = delete;
Actuator(Actuator const&) = delete;
Actuator& operator = (Actuator const&) = default;
Actuator(Actuator&&) = default;
Actuator& operator = (Actuator&&) = default;
ActuatorInterface(Driver& driver, std::uint32_t const actuator_id);
ActuatorInterface() = delete;
ActuatorInterface(ActuatorInterface const&) = default;
ActuatorInterface& operator = (ActuatorInterface const&) = default;
ActuatorInterface(ActuatorInterface&&) = default;
ActuatorInterface& operator = (ActuatorInterface&&) = default;

/**\fn getAcceleration
* \brief
Expand Down Expand Up @@ -300,14 +299,14 @@ namespace myactuator_rmd {
*/
void setAcceleration(std::uint32_t const acceleration, AccelerationType const mode);

/**\fn setBaudRate
/**\fn setCanBaudRate
* \brief
* Set the communication Baud rate
* Set the communication Baud rate for CAN bus
*
* \param[in] baud_rate
* Communication Baud rate that the actuator should operator with
*/
void setBaudRate(BaudRate const baud_rate);
void setCanBaudRate(CanBaudRate const baud_rate);

/**\fn setCanId
* \brief
Expand Down Expand Up @@ -374,8 +373,12 @@ namespace myactuator_rmd {
* Stop the motor if running closed loop command
*/
void stopMotor();

protected:
Driver& driver_;
std::uint32_t actuator_id_;
};

}

#endif // MYACTUATOR_RMD__ACTUATOR
#endif // MYACTUATOR_RMD__ACTUATOR_INTERFACE
6 changes: 3 additions & 3 deletions include/myactuator_rmd/actuator_state/acceleration_type.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__ACCELERATION_TYPE
#define MYACTUATOR_RMD__ACCELERATION_TYPE
#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__ACCELERATION_TYPE
#define MYACTUATOR_RMD__ACTUATOR_STATE__ACCELERATION_TYPE
#pragma once

#include <cstdint>
Expand All @@ -29,4 +29,4 @@ namespace myactuator_rmd {

}

#endif // MYACTUATOR_RMD__ACCELERATION_TYPE
#endif // MYACTUATOR_RMD__ACTUATOR_STATE__ACCELERATION_TYPE
29 changes: 0 additions & 29 deletions include/myactuator_rmd/actuator_state/baud_rate.hpp

This file was deleted.

29 changes: 29 additions & 0 deletions include/myactuator_rmd/actuator_state/can_baud_rate.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
/**
* \file can_baud_rate.hpp
* \mainpage
* Communication Baud rate of the CAN bus
* \author
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__CAN_BAUD_RATE
#define MYACTUATOR_RMD__ACTUATOR_STATE__CAN_BAUD_RATE
#pragma once

#include <cstdint>


namespace myactuator_rmd {

/**\enum CanBaudRate
* \brief
* Communication Baud rate of the CAN bus
*/
enum class CanBaudRate: std::uint8_t {
KBPS500 = 0,
MBPS1 = 1
};

}

#endif // MYACTUATOR_RMD__ACTUATOR_STATE__CAN_BAUD_RATE
6 changes: 3 additions & 3 deletions include/myactuator_rmd/actuator_state/control_mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__CONTROL_MODE
#define MYACTUATOR_RMD__CONTROL_MODE
#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__CONTROL_MODE
#define MYACTUATOR_RMD__ACTUATOR_STATE__CONTROL_MODE
#pragma once

#include <cstdint>
Expand All @@ -28,4 +28,4 @@ namespace myactuator_rmd {

}

#endif // MYACTUATOR_RMD__CONTROL_MODE
#endif // MYACTUATOR_RMD__ACTUATOR_STATE__CONTROL_MODE
6 changes: 3 additions & 3 deletions include/myactuator_rmd/actuator_state/error_code.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__ERROR_CODE
#define MYACTUATOR_RMD__ERROR_CODE
#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__ERROR_CODE
#define MYACTUATOR_RMD__ACTUATOR_STATE__ERROR_CODE
#pragma once

#include <cstdint>
Expand Down Expand Up @@ -36,4 +36,4 @@ namespace myactuator_rmd {

}

#endif // MYACTUATOR_RMD__ERROR_CODE
#endif // MYACTUATOR_RMD__ACTUATOR_STATE__ERROR_CODE
6 changes: 3 additions & 3 deletions include/myactuator_rmd/actuator_state/feedback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__FEEDBACK
#define MYACTUATOR_RMD__FEEDBACK
#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__FEEDBACK
#define MYACTUATOR_RMD__ACTUATOR_STATE__FEEDBACK
#pragma once

#include "myactuator_rmd/actuator_state/motor_status_2.hpp"
Expand All @@ -20,4 +20,4 @@ namespace myactuator_rmd {

}

#endif // MYACTUATOR_RMD__FEEDBACK
#endif // MYACTUATOR_RMD__ACTUATOR_STATE__FEEDBACK
6 changes: 3 additions & 3 deletions include/myactuator_rmd/actuator_state/gains.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
* Tobit Flatscher (github.com/2b-t)
*/

#ifndef MYACTUATOR_RMD__GAINS
#define MYACTUATOR_RMD__GAINS
#ifndef MYACTUATOR_RMD__ACTUATOR_STATE__GAINS
#define MYACTUATOR_RMD__ACTUATOR_STATE__GAINS
#pragma once

#include <cstdint>
Expand Down Expand Up @@ -107,4 +107,4 @@ namespace myactuator_rmd {

}

#endif // MYACTUATOR_RMD__GAINS
#endif // MYACTUATOR_RMD__ACTUATOR_STATE__GAINS
Loading

0 comments on commit 9ee21fb

Please sign in to comment.