Skip to content

Commit

Permalink
[trajoptlib] Build and publish rust docs
Browse files Browse the repository at this point in the history
TODO
- [ ] document constraints

Resolves SleipnirGroup#942

Signed-off-by: Jade Turner <[email protected]>
  • Loading branch information
spacey-sooty committed Nov 25, 2024
1 parent c3130d1 commit 960897f
Show file tree
Hide file tree
Showing 6 changed files with 180 additions and 45 deletions.
2 changes: 2 additions & 0 deletions make-docs.sh
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,13 @@ popd
pushd trajoptlib
mkdir -p build/docs
doxygen docs/Doxyfile
cargo doc
popd

mkdir -p site/api/{choreolib,trajoptlib}
cp -r choreolib/build/docs/javadoc site/api/choreolib/java
cp -r choreolib/build/docs/cpp/html site/api/choreolib/cpp
cp -r trajoptlib/build/docs/html site/api/trajoptlib/cpp
cp -r target/docs/trajoptlib site/api/trajoptlib/rs

mkdocs build --dirty
22 changes: 11 additions & 11 deletions trajoptlib/include/trajopt/DifferentialTrajectoryGenerator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,13 @@ struct TRAJOPT_DLLEXPORT DifferentialDrivetrain {
/// The moment of inertia of the robot about the origin (kg−m²).
double moi;

/// Radius of wheel (m).
/// Radius of the wheels (m).
double wheelRadius;

/// Maximum angular velocity of wheel (rad/s).
/// Maximum angular velocity of the wheels (rad/s).
double wheelMaxAngularVelocity;

/// Maximum torque applied to wheel (N−m).
/// Maximum torque applied to the wheels (N−m).
double wheelMaxTorque;

/// The Coefficient of Friction (CoF) of the wheels.
Expand Down Expand Up @@ -97,22 +97,22 @@ class TRAJOPT_DLLEXPORT DifferentialTrajectorySample {
/// The heading.
double heading = 0.0;

/// The left wheel velocity.
/// The left wheel's velocity.
double velocityL = 0.0;

/// The right wheel velocity.
/// The right wheel's velocity.
double velocityR = 0.0;

/// The left wheel acceleration.
/// The left wheel's acceleration.
double accelerationL = 0.0;

/// The right wheel acceleration.
/// The right wheel's acceleration.
double accelerationR = 0.0;

/// The left wheel force.
/// The left wheel's force.
double forceL = 0.0;

/// The right wheel force.
/// The right wheel's force.
double forceR = 0.0;

DifferentialTrajectorySample() = default;
Expand Down Expand Up @@ -152,15 +152,15 @@ class TRAJOPT_DLLEXPORT DifferentialTrajectorySample {
*/
class TRAJOPT_DLLEXPORT DifferentialTrajectory {
public:
/// Trajectory samples.
/// The samples that make up the trajectory.
std::vector<DifferentialTrajectorySample> samples;

DifferentialTrajectory() = default;

/**
* Construct a DifferentialTrajectory from samples.
*
* @param samples The samples.
* @param samples The samples that make up the trajectory.
*/
explicit DifferentialTrajectory(
std::vector<DifferentialTrajectorySample> samples)
Expand Down
10 changes: 5 additions & 5 deletions trajoptlib/include/trajopt/SwerveTrajectoryGenerator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,13 @@ struct TRAJOPT_DLLEXPORT SwerveDrivetrain {
/// The moment of inertia of the robot about the origin (kg−m²).
double moi;

/// Radius of wheel (m).
/// Radius of the wheels (m).
double wheelRadius;

/// Maximum angular velocity of wheel (rad/s).
/// Maximum angular velocity of each wheel (rad/s).
double wheelMaxAngularVelocity;

/// Maximum torque applied to wheel (N−m).
/// Maximum torque applied to each wheel (N−m).
double wheelMaxTorque;

/// The Coefficient of Friction (CoF) of the wheels.
Expand Down Expand Up @@ -173,15 +173,15 @@ class TRAJOPT_DLLEXPORT SwerveTrajectorySample {
*/
class TRAJOPT_DLLEXPORT SwerveTrajectory {
public:
/// Trajectory samples.
/// The samples that make up the trajectory.
std::vector<SwerveTrajectorySample> samples;

SwerveTrajectory() = default;

/**
* Construct a SwerveTrajectory from samples.
*
* @param samples The samples.
* @param samples The samples that make up the trajectory.
*/
explicit SwerveTrajectory(std::vector<SwerveTrajectorySample> samples)
: samples{std::move(samples)} {}
Expand Down
2 changes: 1 addition & 1 deletion trajoptlib/include/trajopt/path/PathBuilder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ template <typename Drivetrain, typename Solution>
class TRAJOPT_DLLEXPORT PathBuilder {
public:
/**
* Set the Drivetrain object
* Set the Drivetrain object.
*
* @param drivetrain the new drivetrain
*/
Expand Down
12 changes: 11 additions & 1 deletion trajoptlib/src/error.rs
Original file line number Diff line number Diff line change
@@ -1,27 +1,37 @@
use thiserror::Error;

#[derive(Debug, Error)]
// messages taken from https://github.com/SleipnirGroup/Sleipnir/blob/main/include/sleipnir/optimization/SolverExitCondition.hpp#L47-L78
/// Represents an error returned by Trajoptlib. Primarily exposes the Sleipnir [Solver Exit
/// Condition](https://github.com/SleipnirGroup/Sleipnir/blob/main/include/sleipnir/optimization/SolverExitCondition.hpp#L47-L78)
pub enum TrajoptError {
#[error("The solver determined the problem to be overconstrained and gave up")]
/// The solver determined the problem to be overconstrained and gave up
TooFewDOF,
#[error("The solver determined the problem to be locally infeasible and gave up")]
/// The solver determined the problem to be locally infeasible and gave up
LocallyInfeasible,
#[error("The solver failed to reach the desired tolerance, and feasibility restoration failed to converge")]
/// The solver failed to reach the desired tolerance, and feasibility restoration failed to converge
FeasibilityRestorationFailed,
#[error("The solver encountered nonfinite initial cost or constraints and gave up")]
/// The solver encountered nonfinite initial cost or constraints and gave up
NonfiniteInitialCostOrConstraints,
#[error("The solver encountered diverging primal iterates xₖ and/or sₖ and gave up")]
/// The solver encountered diverging primal iterates xₖ and/or sₖ and gave up
DivergingIterates,
#[error(
"The solver returned its solution so far after exceeding the maximum number of iterations"
)]
/// The solver returned its solution so far after exceeding the maximum number of iterations
MaxIterationsExceeded,
#[error("The solver returned its solution so far after exceeding the maximum elapsed wall clock time")]
/// The solver returned its solution so far after exceeding the maximum elapsed wall clock time
Timeout,
#[error("The solver returned an unparsable error code: {0}")]
/// The solver returned an unparsable error code
Unparsable(Box<str>),
#[error("Unknown error: {0:?}")]
/// Unknown error type
Unknown(i8),
}

Expand Down
Loading

0 comments on commit 960897f

Please sign in to comment.