diff --git a/docs/source/tutorials_general/racing.cpp b/docs/source/tutorials_general/racing.cpp index dc3e64ff37..ef634db2e2 100644 --- a/docs/source/tutorials_general/racing.cpp +++ b/docs/source/tutorials_general/racing.cpp @@ -82,8 +82,8 @@ int main(int argc, char *argv[]) { std::size_t num_waypoints = way_points.size(); Eigen::VectorXd segment_times(num_waypoints); segment_times << 10.0, 10.0, 10.0, 10.0; - Eigen::VectorXd minimization_weights(num_waypoints); - minimization_weights << 1.0, 1.0, 1.0, 1.0; + Eigen::VectorXd minimization_weights(5); + minimization_weights << 0.0, 1.0, 1.0, 1.0, 1.0; polynomial_trajectories::PolynomialTrajectorySettings trajectory_settings = polynomial_trajectories::PolynomialTrajectorySettings( diff --git a/docs/source/tutorials_general/racing.rst b/docs/source/tutorials_general/racing.rst index 7cc806af4d..61780c0d7b 100644 --- a/docs/source/tutorials_general/racing.rst +++ b/docs/source/tutorials_general/racing.rst @@ -23,8 +23,8 @@ Generate trajectory std::size_t num_waypoints = way_points.size(); Eigen::VectorXd segment_times(num_waypoints); segment_times << 10.0, 10.0, 10.0, 10.0; - Eigen::VectorXd minimization_weights(num_waypoints); - minimization_weights << 1.0, 1.0, 1.0, 1.0; + Eigen::VectorXd minimization_weights(5); + minimization_weights << 0.0, 1.0, 1.0, 1.0, 1.0; polynomial_trajectories::PolynomialTrajectorySettings trajectory_settings = polynomial_trajectories::PolynomialTrajectorySettings( diff --git a/flightros/src/racing/racing.cpp b/flightros/src/racing/racing.cpp index e2873b54c4..5bc6074ddc 100644 --- a/flightros/src/racing/racing.cpp +++ b/flightros/src/racing/racing.cpp @@ -69,8 +69,8 @@ int main(int argc, char *argv[]) { std::size_t num_waypoints = way_points.size(); Eigen::VectorXd segment_times(num_waypoints); segment_times << 10.0, 10.0, 10.0, 10.0; - Eigen::VectorXd minimization_weights(num_waypoints); - minimization_weights << 1.0, 1.0, 1.0, 1.0; + Eigen::VectorXd minimization_weights(5); + minimization_weights << 0.0, 1.0, 1.0, 1.0, 1.0; polynomial_trajectories::PolynomialTrajectorySettings trajectory_settings = polynomial_trajectories::PolynomialTrajectorySettings(