Skip to content

Commit

Permalink
Remove some redundant checks
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Feb 13, 2025
1 parent 820e8b6 commit 2a6e3ad
Showing 1 changed file with 0 additions and 26 deletions.
26 changes: 0 additions & 26 deletions pid_controller/test/test_pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -693,12 +693,6 @@ TEST_F(PidControllerTest, test_save_i_term_off)
}
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_FALSE(controller_->is_in_chained_mode());
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[0]));
EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF);
for (const auto & interface : controller_->reference_interfaces_)
{
EXPECT_TRUE(std::isnan(interface));
}

std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();
msg->dof_names = dof_names_;
Expand All @@ -710,13 +704,6 @@ TEST_F(PidControllerTest, test_save_i_term_off)
msg->values_dot.resize(dof_names_.size(), std::numeric_limits<double>::quiet_NaN());
controller_->input_ref_.writeFromNonRT(msg);

for (size_t i = 0; i < dof_command_values_.size(); ++i)
{
EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i]));
EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]);
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
}

ASSERT_EQ(
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
Expand Down Expand Up @@ -773,12 +760,6 @@ TEST_F(PidControllerTest, test_save_i_term_on)
controller_->set_chained_mode(false);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_FALSE(controller_->is_in_chained_mode());
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[0]));
EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF);
for (const auto & interface : controller_->reference_interfaces_)
{
EXPECT_TRUE(std::isnan(interface));
}

std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();
msg->dof_names = dof_names_;
Expand All @@ -790,13 +771,6 @@ TEST_F(PidControllerTest, test_save_i_term_on)
msg->values_dot.resize(dof_names_.size(), std::numeric_limits<double>::quiet_NaN());
controller_->input_ref_.writeFromNonRT(msg);

for (size_t i = 0; i < dof_command_values_.size(); ++i)
{
EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i]));
EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]);
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
}

ASSERT_EQ(
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
Expand Down

0 comments on commit 2a6e3ad

Please sign in to comment.