Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix multiple system unconfigured rise cleanup #1175

10 changes: 8 additions & 2 deletions hardware_interface/src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,10 @@ const rclcpp_lifecycle::State & Actuator::get_state() const { return impl_->get_

return_type Actuator::read(const rclcpp::Time & time, const rclcpp::Duration & period)
{
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}
return_type result = return_type::ERROR;
if (
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
Expand All @@ -235,7 +238,10 @@ return_type Actuator::read(const rclcpp::Time & time, const rclcpp::Duration & p

return_type Actuator::write(const rclcpp::Time & time, const rclcpp::Duration & period)
{
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}
return_type result = return_type::ERROR;
if (
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
Expand Down
5 changes: 5 additions & 0 deletions hardware_interface/src/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,6 +197,11 @@ return_type Sensor::read(const rclcpp::Time & time, const rclcpp::Duration & per
{
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

return_type result = return_type::ERROR;
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

Comment on lines +200 to +204
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

if (
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
Expand Down
10 changes: 10 additions & 0 deletions hardware_interface/src/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,11 @@ return_type System::read(const rclcpp::Time & time, const rclcpp::Duration & per
{
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

return_type result = return_type::ERROR;
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

Comment on lines +219 to +223
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

if (
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
Expand All @@ -233,6 +238,11 @@ return_type System::write(const rclcpp::Time & time, const rclcpp::Duration & pe
{
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// TODO(destogl): discuss what should be default return value, e.g., "NOT_EXECUTED"
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

return_type result = return_type::ERROR;
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

Comment on lines +241 to +245
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
return return_type::OK;
}

if (
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
Expand Down
12 changes: 6 additions & 6 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -446,17 +446,17 @@ TEST(TestComponentInterfaces, dummy_actuator)

double velocity_value = 1.0;
command_interfaces[0].set_value(velocity_value); // velocity
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD));

// Noting should change because it is UNCONFIGURED
for (auto step = 0u; step < 10; ++step)
{
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.read(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD));

ASSERT_TRUE(std::isnan(state_interfaces[0].get_value())); // position value
ASSERT_TRUE(std::isnan(state_interfaces[1].get_value())); // velocity

ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD));
}

state = actuator_hw.configure();
Expand Down Expand Up @@ -587,12 +587,12 @@ TEST(TestComponentInterfaces, dummy_system)
command_interfaces[0].set_value(velocity_value); // velocity
command_interfaces[1].set_value(velocity_value); // velocity
command_interfaces[2].set_value(velocity_value); // velocity
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.write(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD));

// Noting should change because it is UNCONFIGURED
for (auto step = 0u; step < 10; ++step)
{
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.read(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD));

ASSERT_TRUE(std::isnan(state_interfaces[0].get_value())); // position value
ASSERT_TRUE(std::isnan(state_interfaces[1].get_value())); // velocity
Expand All @@ -601,7 +601,7 @@ TEST(TestComponentInterfaces, dummy_system)
ASSERT_TRUE(std::isnan(state_interfaces[4].get_value())); // position value
ASSERT_TRUE(std::isnan(state_interfaces[5].get_value())); // velocity

ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.write(TIME, PERIOD));
ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD));
}

state = system_hw.configure();
Expand Down
Loading