Skip to content

Commit

Permalink
Use return value for configure/activate of other tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 25, 2023
1 parent db55d28 commit 0328e54
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 13 deletions.
18 changes: 7 additions & 11 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,8 +181,8 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
rclcpp::executors::MultiThreadedExecutor executor;
SetUpTrajectoryController(executor);

traj_controller_->get_node()->configure();
ASSERT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_INACTIVE);
auto state = traj_controller_->get_node()->configure();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);

auto cmd_interface_config = traj_controller_->command_interface_configuration();
ASSERT_EQ(
Expand All @@ -192,8 +192,8 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
ASSERT_EQ(
state_interface_config.names.size(), joint_names_.size() * state_interface_types_.size());

ActivateTrajectoryController();
ASSERT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_ACTIVE);
state = ActivateTrajectoryController();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_ACTIVE);

executor.cancel();
}
Expand Down Expand Up @@ -253,13 +253,10 @@ TEST_P(TrajectoryControllerTestParameterized, correct_initialization_using_param
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true));

// This call is replacing the way parameters are set via launch
traj_controller_->configure();
auto state = traj_controller_->get_state();
auto state = traj_controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());

ActivateTrajectoryController();

state = traj_controller_->get_state();
state = ActivateTrajectoryController();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
EXPECT_EQ(INITIAL_POS_JOINT1, joint_pos_[0]);
EXPECT_EQ(INITIAL_POS_JOINT2, joint_pos_[1]);
Expand Down Expand Up @@ -304,8 +301,7 @@ TEST_P(TrajectoryControllerTestParameterized, correct_initialization_using_param
// wait so controller would have processed the third point when reactivated -> but it shouldn't
std::this_thread::sleep_for(std::chrono::milliseconds(3000));

ActivateTrajectoryController(false, deactivated_positions);
state = traj_controller_->get_state();
state = ActivateTrajectoryController(false, deactivated_positions);
ASSERT_EQ(state.id(), State::PRIMARY_STATE_ACTIVE);

// it should still be holding the position at time of deactivation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ class TrajectoryControllerTest : public ::testing::Test
initial_eff_joints);
}

void ActivateTrajectoryController(
rclcpp_lifecycle::State ActivateTrajectoryController(
bool separate_cmd_and_state_values = false,
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS,
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
Expand Down Expand Up @@ -319,7 +319,7 @@ class TrajectoryControllerTest : public ::testing::Test
}

traj_controller_->assign_interfaces(std::move(cmd_interfaces), std::move(state_interfaces));
traj_controller_->get_node()->activate();
return traj_controller_->get_node()->activate();
}

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

0 comments on commit 0328e54

Please sign in to comment.