Skip to content

Commit

Permalink
Change "LEDRgbDevice" to "LedRgbDevice"
Browse files Browse the repository at this point in the history
  • Loading branch information
Thibault Poignonec committed Dec 20, 2024
1 parent 121da64 commit ab32971
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,14 @@

namespace semantic_components
{
class LEDRgbDevice : public SemanticComponentCommandInterface<std_msgs::msg::ColorRGBA>
class LedRgbDevice : public SemanticComponentCommandInterface<std_msgs::msg::ColorRGBA>
{
public:
/**
* Constructor for a LED RGB device with interface names set based on device name.
* The constructor sets the command interface names to "<name>/r", "<name>/g", "<name>/b".
*/
explicit LEDRgbDevice(const std::string & name) : SemanticComponentCommandInterface(name, 3)
explicit LedRgbDevice (const std::string & name) : SemanticComponentCommandInterface(name, 3)
{
interface_names_.emplace_back(name_ + "/" + "r");
interface_names_.emplace_back(name_ + "/" + "g");
Expand All @@ -42,7 +42,7 @@ class LEDRgbDevice : public SemanticComponentCommandInterface<std_msgs::msg::Col
* Constructor for a LED RGB device with custom interface names.
* The constructor takes the three command interface names for the red, green, and blue channels.
*/
explicit LEDRgbDevice(
explicit LedRgbDevice (
const std::string & interface_r, const std::string & interface_g,
const std::string & interface_b)
: SemanticComponentCommandInterface("", 3)
Expand All @@ -52,7 +52,7 @@ class LEDRgbDevice : public SemanticComponentCommandInterface<std_msgs::msg::Col
interface_names_.emplace_back(interface_b);
}

virtual ~LEDRgbDevice() = default;
virtual ~LedRgbDevice () = default;

/// Set LED states from ColorRGBA message
bool set_values_from_message(std_msgs::msg::ColorRGBA & message)
Expand Down
6 changes: 3 additions & 3 deletions controller_interface/test/test_led_rgb_device.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,19 +25,19 @@

#include "semantic_components/led_rgb_device.hpp"

class TestableLedDevice : public semantic_components::LEDRgbDevice
class TestableLedDevice : public semantic_components::LedRgbDevice
{
FRIEND_TEST(LedDeviceTest, validate_all);
FRIEND_TEST(LedDeviceTest, validate_custom_names);

public:
// Use default command interface names
explicit TestableLedDevice(const std::string & name) : LEDRgbDevice{name} {}
explicit TestableLedDevice(const std::string & name) : LedRgbDevice {name} {}

TestableLedDevice(
const std::string & interface_r, const std::string & interface_g,
const std::string & interface_b)
: LEDRgbDevice{interface_r, interface_g, interface_b}
: LedRgbDevice {interface_r, interface_g, interface_b}
{
}

Expand Down

0 comments on commit ab32971

Please sign in to comment.