Skip to content

Commit

Permalink
redecorating
Browse files Browse the repository at this point in the history
Co-authored-by: Dr. Denis <[email protected]>
Co-authored-by: Christoph Fröhlich <[email protected]>
  • Loading branch information
3 people authored Sep 25, 2024
1 parent 50c7b9e commit f2adeb1
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 10 deletions.
1 change: 0 additions & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -672,7 +672,6 @@ class ResourceStorage

hardware_info_map_[hardware.get_name()].command_interfaces =
add_command_interfaces(interfaces);
// TODO(Manuel) END: for backward compatibility
}
catch (const std::exception & ex)
{
Expand Down
2 changes: 0 additions & 2 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,6 @@ class DummySensorDefault : public hardware_interface::SensorInterface
return hardware_interface::CallbackReturn::ERROR;
}

// We hardcode the info
return CallbackReturn::SUCCESS;
}

Expand Down Expand Up @@ -524,7 +523,6 @@ class DummySystemDefault : public hardware_interface::SystemInterface
{
return hardware_interface::CallbackReturn::ERROR;
}
// We hardcode the info
return CallbackReturn::SUCCESS;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@
#include "ros2_control_test_assets/descriptions.hpp"
#include "test_components.hpp"

// Values to send over command interface to trigger error in write and read methods

namespace
{
const auto TIME = rclcpp::Time(0);
Expand All @@ -57,7 +55,8 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
{
std::string get_name() const override { return "DummyActuatorDefault"; }

std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interface_descriptions()
std::vector<hardware_interface::InterfaceDescription>
export_unlisted_state_interface_descriptions()
override
{
std::vector<hardware_interface::InterfaceDescription> interfaces;
Expand All @@ -69,7 +68,8 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
return interfaces;
}

std::vector<hardware_interface::InterfaceDescription> export_unlisted_command_interface_descriptions()
std::vector<hardware_interface::InterfaceDescription>
export_unlisted_command_interface_descriptions()
override
{
std::vector<hardware_interface::InterfaceDescription> interfaces;
Expand Down Expand Up @@ -98,7 +98,8 @@ class DummySensorDefault : public hardware_interface::SensorInterface
{
std::string get_name() const override { return "DummySensorDefault"; }

std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interface_descriptions()
std::vector<hardware_interface::InterfaceDescription>
export_unlisted_state_interface_descriptions()
override
{
std::vector<hardware_interface::InterfaceDescription> interfaces;
Expand All @@ -121,7 +122,8 @@ class DummySystemDefault : public hardware_interface::SystemInterface
{
std::string get_name() const override { return "DummySystemDefault"; }

std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interface_descriptions()
std::vector<hardware_interface::InterfaceDescription>
export_unlisted_state_interface_descriptions()
override
{
std::vector<hardware_interface::InterfaceDescription> interfaces;
Expand All @@ -133,7 +135,8 @@ class DummySystemDefault : public hardware_interface::SystemInterface
return interfaces;
}

std::vector<hardware_interface::InterfaceDescription> export_unlisted_command_interface_descriptions()
std::vector<hardware_interface::InterfaceDescription>
export_unlisted_command_interface_descriptions()
override
{
std::vector<hardware_interface::InterfaceDescription> interfaces;
Expand Down

0 comments on commit f2adeb1

Please sign in to comment.