I have been following several examples in defining a custom hardware interface using ros2_control
in ROS2 Humble. I am trying to replicate these concepts for a prismatic joint, controlled with a velocity servo. Like the examples, my script inherits multiple virtual functions from the hardware_interface::SystemInterface
class. Most of these virtual functions are correctly overridden, but the two pure virtual functions read
and write
generate the following error:
In file included from /ros2_ws/src/linear-slider/linear_slider_controller/src/linear_slider_system_interface.cpp:1:
/ros2_ws/src/linear-slider/linear_slider_controller/include/linear_slider_controller/linear_slider_system_interface.hpp:60:45: error: ‘hardware_interface::return_type linear_slider_system_interface::LinearSliderSystemInterface::read(const rclcpp::Time&, rclcpp::Duration&)’ marked ‘override’, but does not override
60 | hardware_interface::return_type read(const rclcpp::Time& time, rclcpp::Duration& period) override;
| ^~~~
/ros2_ws/src/linear-slider/linear_slider_controller/include/linear_slider_controller/linear_slider_system_interface.hpp:63:45: error: ‘hardware_interface::return_type linear_slider_system_interface::LinearSliderSystemInterface::write(const rclcpp::Time&, rclcpp::Duration&)’ marked ‘override’, but does not override
63 | hardware_interface::return_type write(const rclcpp::Time& time, rclcpp::Duration& period) override;
|
/opt/ros/humble/include/class_loader/class_loader/meta_object.hpp: In instantiation of ‘B* class_loader::impl::MetaObject<C, B>::create() const [with C = linear_slider_system_interface::LinearSliderSystemInterface; B = hardware_interface::SystemInterface]’:
/opt/ros/humble/include/class_loader/class_loader/meta_object.hpp:216:7: required from here
/opt/ros/humble/include/class_loader/class_loader/meta_object.hpp:218:12: error: invalid new-expression of abstract class type ‘linear_slider_system_interface::LinearSliderSystemInterface’
218 | return new C;
| ^~~~~
In file included from /ros2_ws/src/linear-slider/linear_slider_controller/src/linear_slider_system_interface.cpp:1:
/ros2_ws/src/linear-slider/linear_slider_controller/include/linear_slider_controller/linear_slider_system_interface.hpp:28:11: note: because the following virtual functions are pure within ‘linear_slider_system_interface::LinearSliderSystemInterface’:
28 | class LinearSliderSystemInterface : public hardware_interface::SystemInterface
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /ros2_ws/src/linear-slider/linear_slider_controller/include/linear_slider_controller/linear_slider_system_interface.hpp:12,
from /ros2_ws/src/linear-slider/linear_slider_controller/src/linear_slider_system_interface.cpp:1:
/opt/ros/humble/include/hardware_interface/system_interface.hpp:175:23: note: ‘virtual hardware_interface::return_type hardware_interface::SystemInterface::read(const rclcpp::Time&, const rclcpp::Duration&)’
175 | virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
| ^~~~
/opt/ros/humble/include/hardware_interface/system_interface.hpp:186:23: note: ‘virtual hardware_interface::return_type hardware_interface::SystemInterface::write(const rclcpp::Time&, const rclcpp::Duration&)’
186 | virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
| ^~~~~
I am overriding the SystemInterface::export_command_interfaces()
and SystemInterface::export_state_interfaces()
methods correctly, as I do not get this error. After many reviews, I cannot find any notable differences between my implementation and the examples I have been following, including the demo examples from the ros2_control_demos repository. Can you spot where I am going wrong in this override?
My code is below:
linear_slider_system_interface.hpp:
#ifndef __LINEAR_SLIDER_CONTROLLER__HARDWARE_INTERFACE_H__
#define __LINEAR_SLIDER_CONTROLLER__HARDWARE_INTERFACE_H__
#include <chrono>
#include <cstdint>
#include <memory>
#include <string>
#include <vector>
#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "linear_slider_controller/visibility_control.h"
#include "linear_slider_controller/clearcore_comms.hpp"
#include "linear_slider_controller/teknic_motor.hpp"
namespace linear_slider_system_interface
{
class LinearSliderSystemInterface : public hardware_interface::SystemInterface
{
public:
RCLCPP_SHARED_PTR_DEFINITIONS(LinearSliderSystemInterface)
LINEAR_SLIDER_CONTROLLER_PUBLIC
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
LINEAR_SLIDER_CONTROLLER_PUBLIC
std::vector<hardware_interface::StateInterface> export_state_interfaces() override; // publishes to the rest of ros2_control so that we know what we can read/write to
LINEAR_SLIDER_CONTROLLER_PUBLIC
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
LINEAR_SLIDER_CONTROLLER_PUBLIC
hardware_interface::return_type read(const rclcpp::Time& time, rclcpp::Duration& period) override;
LINEAR_SLIDER_CONTROLLER_PUBLIC
hardware_interface::return_type write(const rclcpp::Time& time, rclcpp::Duration& period) override;
private:
// Comms
ClearCoreComms comms_;
// Teknic Motor
TeknicMotor teknic_motor_;
};
} // namespace linear_slider_system_interface
#endif // __LINEAR_SLIDER_CONTROLLER__HARDWARE_INTERFACE_H__
linear_slider_system_interface.cpp:
#include "linear_slider_controller/linear_slider_system_interface.hpp"
#include <chrono>
#include <memory>
#include <cmath>
#include <limits>
#include <string>
#include <vector>
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"
namespace linear_slider_system_interface
{
hardware_interface::CallbackReturn LinearSliderSystemInterface::on_init(const hardware_interface::HardwareInfo& info) {
/* Checks whether the hardware interface matches the robot description */
if (hardware_interface::SystemInterface::on_init(info) != hardware_interface::CallbackReturn::SUCCESS) {
return hardware_interface::CallbackReturn::ERROR;
}
// Set up motor
teknic_motor_.begin("teknic_clearpath_mc");
for (const hardware_interface::ComponentInfo& joint : info_.joints) {
// The linear slider has one state and one command interface on the single prismatic joint, make sure they exist
// Command interface check
if (joint.command_interfaces.size() != 1) {
RCLCPP_FATAL(
rclcpp::get_logger("LinearSliderSystemHardware"),
"Joint '%s' has %zu command interfaces found. 1 expected.",
joint.name.c_str(),
joint.command_interfaces.size()
);
return hardware_interface::CallbackReturn::ERROR;
}
if (!(joint.command_interfaces[0].name == hardware_interface::HW_IF_VELOCITY)) {
RCLCPP_FATAL(
rclcpp::get_logger("LinearSliderSystemHardware"),
"Joint '%s' has %s command interface. Expected %s.",
joint.name.c_str(),
joint.command_interfaces[0].name.c_str(),
hardware_interface::HW_IF_VELOCITY
);
return hardware_interface::CallbackReturn::ERROR;
}
// State interface check
if (joint.state_interfaces.size() != 1) {
RCLCPP_FATAL(
rclcpp::get_logger("LinearSliderSystemHardware"),
"Joint '%s' has %zu state interfaces. 1 expected.",
joint.name.c_str(),
joint.state_interfaces.size()
);
return hardware_interface::CallbackReturn::ERROR;
}
if (!(joint.state_interfaces[0].name == hardware_interface::HW_IF_VELOCITY)) {
RCLCPP_FATAL(
rclcpp::get_logger("LinearSliderSystemHardware"),
"Joint '%s' has %s state interface. Expected %s.",
joint.name.c_str(),
joint.state_interfaces[0].name.c_str(),
hardware_interface::HW_IF_VELOCITY
);
return hardware_interface::CallbackReturn::ERROR;
}
}
return hardware_interface::CallbackReturn::SUCCESS;
}
std::vector<hardware_interface::CommandInterface> LinearSliderSystemInterface::export_command_interfaces() {
/* Tells the rest of ros2_control which control interfaces are accessible */
std::vector<hardware_interface::CommandInterface> command_interfaces;
command_interfaces.emplace_back(hardware_interface::CommandInterface(
teknic_motor_.name, hardware_interface::HW_IF_VELOCITY, &teknic_motor_.vel_cmd
));
return command_interfaces;
}
std::vector<hardware_interface::StateInterface> LinearSliderSystemInterface::export_state_interfaces() {
/* Tells the rest of ros2_control which state interfaces are accessible */
std::vector<hardware_interface::StateInterface> state_interfaces;
state_interfaces.emplace_back(hardware_interface::StateInterface(
teknic_motor_.name, hardware_interface::HW_IF_VELOCITY, &teknic_motor_.vel_state
));
}
hardware_interface::return_type LinearSliderSystemInterface::read(const rclcpp::Time & time, rclcpp::Duration & period) {
/* Read data from the linear slider. Converts RPM speeds to linear velocities */
char* msg = comms_.read_data();
if (msg[0] != '\0'){
// convert rpm message to float velocity, store in teknic_motor_.rpm_state. Additionally, update teknic_motor_.vel_state
}
return hardware_interface::return_type::OK;
}
hardware_interface::return_type LinearSliderSystemInterface::write(const rclcpp::Time & time, rclcpp::Duration & period) {
/* Write data to the linear slider. Converts linear velocities to RPM speeds */
// convert teknic_motor_.vel_cmd to teknic_motor_.rpm_cmd. Convert this value to str, send via comms_
teknic_motor_.rpm_cmd = teknic_motor_.vel_to_rpm(teknic_motor_.vel_cmd); // TODO: this should probably either be completely internal, or completely external, but not both.
std::string cmd = std::to_string(teknic_motor_.rpm_cmd);
comms_.send_data(cmd.c_str());
return hardware_interface::return_type::OK;
}
} // namespace linear_slider_system_interface
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(
linear_slider_system_interface::LinearSliderSystemInterface, hardware_interface::SystemInterface
)
Thank you for any help, it is greatly appreciated. Please let me know if I missed sharing any important information.