Skip to content

Commit

Permalink
feat: Add setting actuator communication interruption protection time
Browse files Browse the repository at this point in the history
  • Loading branch information
2b-t committed Nov 19, 2023
1 parent d4a175a commit 5c1454d
Show file tree
Hide file tree
Showing 8 changed files with 77 additions and 1 deletion.
2 changes: 2 additions & 0 deletions bindings/myactuator_rmd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <pybind11/stl.h>

#include "myactuator_rmd/actuator_state/acceleration_function_index.hpp"
#include "myactuator_rmd/actuator_state/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 Down Expand Up @@ -62,6 +63,7 @@ PYBIND11_MODULE(myactuator_rmd, m) {
.def("setBaudRate", &myactuator_rmd::Driver::setBaudRate)
.def("setCanId", &myactuator_rmd::Driver::setCanId)
.def("setControllerGains", &myactuator_rmd::Driver::setControllerGains)
.def("setTimeout", &myactuator_rmd::Driver::setTimeout)
.def("shutdownMotor", &myactuator_rmd::Driver::shutdownMotor)
.def("stopMotor", &myactuator_rmd::Driver::stopMotor);
pybind11::register_exception<myactuator_rmd::Exception>(m, "DriverException");
Expand Down
10 changes: 10 additions & 0 deletions include/myactuator_rmd/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,16 @@ namespace myactuator_rmd {
*/
Gains setControllerGains(Gains const& gains, bool const is_persistent = false);

/**\fn setTimeout
* \brief
* Set the communication interruption protection time setting. The break will be triggered if the communication
* is interrupted for longer than the set time. The value 0 disables this feature.
*
* \param[in] timeout
* The desired interruption protection time, 0 in case it should be disabled
*/
void setTimeout(std::chrono::milliseconds const& timeout);

/**\fn shutdownMotor
* \brief
* Turn off the motor
Expand Down
2 changes: 1 addition & 1 deletion include/myactuator_rmd/protocol/command_type.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace myactuator_rmd {
LOCK_BRAKE = 0x78,
READ_SYSTEM_RUNTIME = 0xB1,
READ_SYSTEM_SOFTWARE_VERSION_DATE = 0xB2,
// COMMUNICATION_INTERRUPTION_PROTECTION_TIME_SETTING = 0xB3,
COMMUNICATION_INTERRUPTION_PROTECTION_TIME_SETTING = 0xB3,
COMMUNICATION_BAUD_RATE_SETTING = 0xB4,
READ_MOTOR_MODEL = 0xB5,
// FUNCTION_CONTROL = 0x20,
Expand Down
33 changes: 33 additions & 0 deletions include/myactuator_rmd/protocol/requests.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#define MYACTUATOR_RMD__PROTOCOL__REQUESTS
#pragma once

#include <chrono>
#include <cstdint>

#include "myactuator_rmd/actuator_state/baud_rate.hpp"
Expand Down Expand Up @@ -279,6 +280,38 @@ namespace myactuator_rmd {
float getPosition() const noexcept;
};

/**\class SetTimeoutRequest
* \brief
* Request for setting the communication interruption protection time setting
*/
class SetTimeoutRequest: public SingleMotorRequest<CommandType::COMMUNICATION_INTERRUPTION_PROTECTION_TIME_SETTING> {
public:
/**\fn SetTimeoutRequest
* \brief
* Class constructor
*
* \param[in] timeout
* The communication interruption protection time setting in milliseconds, 0 if this feature should be de-activated
*/
SetTimeoutRequest(std::chrono::milliseconds const& timeout);
SetTimeoutRequest() = delete;
SetTimeoutRequest(SetTimeoutRequest const&) = default;
SetTimeoutRequest& operator = (SetTimeoutRequest const&) = default;
SetTimeoutRequest(SetTimeoutRequest&&) = default;
SetTimeoutRequest& operator = (SetTimeoutRequest&&) = default;
using SingleMotorRequest::SingleMotorRequest;

/**\fn getTimeout
* \brief
* Get the communication interruption protection time to be set
*
* \return
* The communication interruption protection time to be set
*/
[[nodiscard]]
std::chrono::milliseconds getTimeout() const noexcept;
};

/**\class SetTorqueRequest
* \brief
* Request for setting the torque of the actuator by setting a target current
Expand Down
1 change: 1 addition & 0 deletions include/myactuator_rmd/protocol/responses.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -465,6 +465,7 @@ namespace myactuator_rmd {

using SetAccelerationResponse = SingleMotorResponse<CommandType::WRITE_ACCELERATION_TO_RAM_AND_ROM>;
using SetCanIdResponse = SingleMotorResponse<CommandType::CAN_ID_SETTING>;
using SetTimeoutResponse = SingleMotorResponse<CommandType::COMMUNICATION_INTERRUPTION_PROTECTION_TIME_SETTING>;
using ShutdownMotorResponse = SingleMotorResponse<CommandType::SHUTDOWN_MOTOR>;
using StopMotorResponse = SingleMotorResponse<CommandType::STOP_MOTOR>;

Expand Down
6 changes: 6 additions & 0 deletions src/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,6 +197,12 @@ namespace myactuator_rmd {
}
}

void Driver::setTimeout(std::chrono::milliseconds const& timeout) {
SetTimeoutRequest const request {timeout};
[[maybe_unused]] auto const response {sendRecv<SetTimeoutResponse>(request)};
return;
}

void Driver::shutdownMotor() {
ShutdownMotorRequest const request {};
[[maybe_unused]] auto const response {sendRecv<ShutdownMotorResponse>(request)};
Expand Down
11 changes: 11 additions & 0 deletions src/protocol/requests.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "myactuator_rmd/protocol/requests.hpp"

#include <chrono>
#include <cstdint>
#include <cstring>
#include <string>
Expand Down Expand Up @@ -99,6 +100,16 @@ namespace myactuator_rmd {
return static_cast<float>(getAs<std::int16_t>(4))*0.01f;
}

SetTimeoutRequest::SetTimeoutRequest(std::chrono::milliseconds const& timeout) {
setAt(static_cast<std::uint32_t>(timeout.count()), 4);
return;
}

std::chrono::milliseconds SetTimeoutRequest::getTimeout() const noexcept {
std::chrono::milliseconds const timeout {getAs<std::uint32_t>(4)};
return timeout;
}

SetVelocityRequest::SetVelocityRequest(float const speed)
: SingleMotorRequest{} {
if ((speed < -1320.0f) || (speed > 1320.0f)) {
Expand Down
13 changes: 13 additions & 0 deletions test/protocol/requests_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
* Tobit Flatscher (github.com/2b-t)
*/

#include <chrono>
#include <cstdint>

#include <gtest/gtest.h>
Expand Down Expand Up @@ -107,6 +108,18 @@ namespace myactuator_rmd {
EXPECT_NEAR(max_speed, 500.0f, 0.1f);
}

TEST(SetTimeoutOffRequestTest, parsing) {
myactuator_rmd::SetTimeoutRequest const request {{0xB3, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
std::chrono::milliseconds const timeout {request.getTimeout()};
EXPECT_EQ(timeout.count(), 0);
}

TEST(SetTimeoutRequestTest, parsing) {
myactuator_rmd::SetTimeoutRequest const request {{0xB3, 0x00, 0x00, 0x00, 0xE8, 0x03, 0x00, 0x00}};
std::chrono::milliseconds const timeout {request.getTimeout()};
EXPECT_EQ(timeout.count(), 1000);
}

TEST(SetTorqueRequestTest, parsingPositiveCurrent) {
myactuator_rmd::SetTorqueRequest const request ({0xA1, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00});
auto const current {request.getTorqueCurrent()};
Expand Down

0 comments on commit 5c1454d

Please sign in to comment.