Skip to content
This repository has been archived by the owner on Nov 22, 2023. It is now read-only.

Commit

Permalink
Simplify check for motion
Browse files Browse the repository at this point in the history
  • Loading branch information
agutenkunst committed Jun 16, 2020
1 parent a3d2592 commit 53f60a7
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 29 deletions.
27 changes: 0 additions & 27 deletions pilz_control/test/pjtc_test_helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,33 +155,6 @@ static bool updateUntilRobotMotion(RobotDriver* robot_driver,
[robot_driver]() { robot_driver->update(); });
}

//! @brief Checks for the specified observation time that the robot does not move.
template <class RobotDriver>
static testing::AssertionResult noExecutionObserving(RobotDriver* robot_driver,
const std::chrono::milliseconds observation_time)
{
const std::chrono::system_clock::time_point start{ std::chrono::system_clock::now() };
while (ros::ok())
{
if (robot_driver->isRobotMoving())
{
return testing::AssertionFailure() << "Controller unexpectedly executed a trajectory.";
}

if (std::chrono::system_clock::now() - start > observation_time)
{
return testing::AssertionSuccess() << "Controller did not execute a trajectory.";
}

progressInTime(ros::Duration(DEFAULT_UPDATE_PERIOD_SEC));
robot_driver->update();

std::this_thread::sleep_for(std::chrono::milliseconds(SLEEP_TIME_MSEC));
}

return testing::AssertionFailure() << "ROS seems to have problems -> motion observation failed.";
}

/**
* @brief Perform init, start, unhold and update, such that controller is ready for executing.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -519,8 +519,8 @@ TEST_P(PilzJointTrajectoryControllerIsExecutingTest, testTrajCommandExecution)
trajectory_command_publisher.publish(goal.trajectory);

ros::Duration observation_time = getGoalDuration(goal) + ros::Duration(DEFAULT_UPDATE_PERIOD_SEC);
EXPECT_TRUE(noExecutionObserving<RobotDriver>(&robot_driver_,
std::chrono::milliseconds(observation_time.toNSec() * 1000000ll)));
EXPECT_FALSE(
updateUntilRobotMotion(&robot_driver_, std::chrono::milliseconds(observation_time.toNSec() * 1000000ll)));
BARRIER(LOG_MSG_RECEIVED_EVENT);
}

Expand Down

0 comments on commit 53f60a7

Please sign in to comment.