Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -693,6 +693,16 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
lifecycle_state_ = new_state;
}

/// Does the state interface exist?
/**
* \param[in] interface_name The name of the state interface.
* \return true if the state interface exists, false otherwise.
*/
bool has_state(const std::string & interface_name) const
{
return hardware_states_.find(interface_name) != hardware_states_.end();
}

/// Set the value of a state interface.
/**
* \tparam T The type of the value to be stored.
Expand Down Expand Up @@ -753,6 +763,16 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
return opt_value.value();
}

/// Does the command interface exist?
/**
* \param[in] interface_name The name of the command interface.
* \return true if the command interface exists, false otherwise.
*/
bool has_command(const std::string & interface_name) const
{
return hardware_commands_.find(interface_name) != hardware_commands_.end();
}

/// Set the value of a command interface.
/**
* \tparam T The type of the value to be stored.
Expand Down
15 changes: 15 additions & 0 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,9 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
{
set_command("joint1/velocity", 0.0);
}
// interfaces are not available
EXPECT_FALSE(has_state("joint1/nonexisting/interface"));
EXPECT_FALSE(has_command("joint1/nonexisting/interface"));
// Should throw as the interface is unknown
EXPECT_THROW(get_state("joint1/nonexisting/interface"), std::runtime_error);
EXPECT_THROW(get_command("joint1/nonexisting/interface"), std::runtime_error);
Expand Down Expand Up @@ -225,6 +228,10 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
{
return hardware_interface::return_type::ERROR;
}
EXPECT_TRUE(has_state("joint1/position"));
EXPECT_TRUE(has_state("joint1/velocity"));
EXPECT_FALSE(has_command("joint1/position")); // only velocity command interface
EXPECT_TRUE(has_command("joint1/velocity"));
auto position_state = get_state("joint1/position");
set_state("joint1/position", position_state + get_command("joint1/velocity"));
set_state("joint1/velocity", get_command("joint1/velocity"));
Expand Down Expand Up @@ -344,6 +351,8 @@ class DummySensorDefault : public hardware_interface::SensorInterface
CallbackReturn on_configure(const rclcpp_lifecycle::State & /*previous_state*/) override
{
set_state("sens1/voltage", 0.0);
// interfaces are not available
EXPECT_FALSE(has_state("joint1/nonexisting/interface"));
// Should throw as the interface is unknown
EXPECT_THROW(get_state("joint1/nonexisting/interface"), std::runtime_error);
EXPECT_THROW(set_state("joint1/nonexisting/interface", 0.0), std::runtime_error);
Expand All @@ -362,6 +371,7 @@ class DummySensorDefault : public hardware_interface::SensorInterface
}

// no-op, static value
EXPECT_TRUE(has_state("sens1/voltage"));
set_state("sens1/voltage", voltage_level_hw_value_);
return hardware_interface::return_type::OK;
}
Expand Down Expand Up @@ -626,6 +636,9 @@ class DummySystemDefault : public hardware_interface::SystemInterface
set_command(velocity_commands_[i], 0.0);
}
}
// interfaces are not available
EXPECT_FALSE(has_state("joint1/nonexisting/interface"));
EXPECT_FALSE(has_command("joint1/nonexisting/interface"));
// Should throw as the interface is unknown
EXPECT_THROW(get_state("joint1/nonexisting/interface"), std::runtime_error);
EXPECT_THROW(get_command("joint1/nonexisting/interface"), std::runtime_error);
Expand Down Expand Up @@ -662,6 +675,8 @@ class DummySystemDefault : public hardware_interface::SystemInterface

for (size_t i = 0; i < 3; ++i)
{
EXPECT_TRUE(has_state(position_states_[i]));
EXPECT_TRUE(has_command(velocity_commands_[i]));
auto current_pos = get_state(position_states_[i]);
set_state(position_states_[i], current_pos + get_command(velocity_commands_[i]));
set_state(velocity_states_[i], get_command(velocity_commands_[i]));
Expand Down
Loading