Skip to content

Commit

Permalink
Exit loop when position can't change.
Browse files Browse the repository at this point in the history
  • Loading branch information
uavster committed Aug 17, 2023
1 parent a2f0183 commit a67e15b
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -325,6 +325,12 @@ Trajectory::Trajectory(const Path& path, const Eigen::VectorXd& max_velocity, co
, time_step_(time_step)
, cached_time_(std::numeric_limits<double>::max())
{
if (time_step_ == 0)
{
valid_ = false;
RCLCPP_ERROR(LOGGER, "The trajectory is invalid because the time step is 0.");
return;
}
trajectory_.push_back(TrajectoryStep(0.0, 0.0));
double after_acceleration = getMinMaxPathAcceleration(0.0, 0.0, true);
while (valid_ && !integrateForward(trajectory_, after_acceleration) && valid_)
Expand Down Expand Up @@ -566,6 +572,16 @@ bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory, double
trajectory.push_back(TrajectoryStep(path_pos, path_vel));
acceleration = getMinMaxPathAcceleration(path_pos, path_vel, true);

if (path_vel == 0 && acceleration == 0)
{
// The position will never change if velocity and acceleration are zero.
// The loop will spin indefinitely as no exit condition is met.
valid_ = false;
RCLCPP_ERROR(LOGGER, "Error while integrating forward: zero acceleration and velocity. Are any relevant "
"acceleration components limited to zero?");
return true;
}

if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
{
// Find more accurate intersection with max-velocity curve using bisection
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -538,6 +538,36 @@ TEST(time_optimal_trajectory_generation, testSingleDofDiscontinuity)
}
}

TEST(time_optimal_trajectory_generation, testRelevantZeroMaxAccelerationsInvalidateTrajectory)
{
const Eigen::Vector2d kMaxVelocity(1, 1);
const Path kPath(std::list<Eigen::VectorXd>{ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 1) });

EXPECT_FALSE(Trajectory(kPath, kMaxVelocity, /*max_acceleration=*/Eigen::Vector2d(0, 1)).isValid());
EXPECT_FALSE(Trajectory(kPath, kMaxVelocity, /*max_acceleration=*/Eigen::Vector2d(1, 0)).isValid());
EXPECT_FALSE(Trajectory(kPath, kMaxVelocity, /*max_acceleration=*/Eigen::Vector2d(0, 0)).isValid());
}

TEST(time_optimal_trajectory_generation, testIrrelevantZeroMaxAccelerationsDontInvalidateTrajectory)
{
const Eigen::Vector2d kMaxVelocity(1, 1);

EXPECT_TRUE(Trajectory(Path(std::list<Eigen::VectorXd>{ Eigen::Vector2d(0, 0), Eigen::Vector2d(0, 1) }), kMaxVelocity,
/*max_acceleration=*/Eigen::Vector2d(0, 1))
.isValid());
EXPECT_TRUE(Trajectory(Path(std::list<Eigen::VectorXd>{ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 0) }), kMaxVelocity,
/*max_acceleration=*/Eigen::Vector2d(1, 0))
.isValid());
}

TEST(time_optimal_trajectory_generation, testTimeStepZeroMakesTrajectoryInvalid)
{
EXPECT_FALSE(Trajectory(Path(std::list<Eigen::VectorXd>{ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 1) }),
/*max_velocity=*/Eigen::Vector2d(1, 1), /*max_acceleration=*/Eigen::Vector2d(1, 1),
/*time_step=*/0)
.isValid());
}

int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down

0 comments on commit a67e15b

Please sign in to comment.