Skip to content

Commit

Permalink
[JTC] Fix the JTC length_error exceptions in the tests (#1360)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Nov 8, 2024
1 parent b0391e2 commit 7ed1a0e
Showing 1 changed file with 18 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "joint_trajectory_controller/tolerances.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "ros2_control_test_assets/descriptions.hpp"

namespace
Expand Down Expand Up @@ -391,6 +392,21 @@ class TrajectoryControllerTest : public ::testing::Test
return traj_controller_->get_node()->activate();
}

void DeactivateTrajectoryController()
{
if (traj_controller_)
{
if (
traj_controller_->get_lifecycle_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
EXPECT_EQ(
traj_controller_->get_node()->deactivate().id(),
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
}
}
}

static void TearDownTestCase() { rclcpp::shutdown(); }

void subscribeToState(rclcpp::Executor & executor)
Expand Down Expand Up @@ -776,6 +792,8 @@ class TrajectoryControllerTestParameterized
state_interface_types_ = std::get<1>(GetParam());
}

virtual void TearDown() { TrajectoryControllerTest::DeactivateTrajectoryController(); }

static void TearDownTestCase() { TrajectoryControllerTest::TearDownTestCase(); }
};

Expand Down

0 comments on commit 7ed1a0e

Please sign in to comment.