Skip to content

Commit

Permalink
Merge branch 'master' into pr-add-gripper-velocity-target-main
Browse files Browse the repository at this point in the history
  • Loading branch information
pac48 authored Apr 9, 2024
2 parents 02aa67a + 9e97c00 commit 72b2f6c
Showing 1 changed file with 0 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,17 +51,13 @@ using lifecycle_msgs::msg::State;
using test_trajectory_controllers::TrajectoryControllerTest;
using test_trajectory_controllers::TrajectoryControllerTestParameterized;

void spin(rclcpp::executors::MultiThreadedExecutor * exe) { exe->spin(); }

TEST_P(TrajectoryControllerTestParameterized, configure_state_ignores_commands)
{
rclcpp::executors::MultiThreadedExecutor executor;
SetUpTrajectoryController(executor);
traj_controller_->get_node()->set_parameter(
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true));

// const auto future_handle_ = std::async(std::launch::async, spin, &executor);

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

Expand Down

0 comments on commit 72b2f6c

Please sign in to comment.