Skip to content

Commit d388667

Browse files
committed
[trajoptlib] Build and publish rust docs
TODO - [ ] document constraints Resolves #942 Signed-off-by: Jade Turner <[email protected]>
1 parent 2f5056d commit d388667

File tree

6 files changed

+180
-45
lines changed

6 files changed

+180
-45
lines changed

make-docs.sh

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,13 @@ popd
1313
pushd trajoptlib
1414
mkdir -p build/docs
1515
doxygen docs/Doxyfile
16+
cargo doc
1617
popd
1718

1819
mkdir -p site/api/{choreolib,trajoptlib}
1920
cp -r choreolib/build/docs/javadoc site/api/choreolib/java
2021
cp -r choreolib/build/docs/cpp/html site/api/choreolib/cpp
2122
cp -r trajoptlib/build/docs/html site/api/trajoptlib/cpp
23+
cp -r target/docs/trajoptlib site/api/trajoptlib/rs
2224

2325
mkdocs build --dirty

trajoptlib/include/trajopt/DifferentialTrajectoryGenerator.hpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,13 @@ struct TRAJOPT_DLLEXPORT DifferentialDrivetrain {
2929
/// The moment of inertia of the robot about the origin (kg−m²).
3030
double moi;
3131

32-
/// Radius of wheel (m).
32+
/// Radius of the wheels (m).
3333
double wheelRadius;
3434

35-
/// Maximum angular velocity of wheel (rad/s).
35+
/// Maximum angular velocity of the wheels (rad/s).
3636
double wheelMaxAngularVelocity;
3737

38-
/// Maximum torque applied to wheel (N−m).
38+
/// Maximum torque applied to the wheels (N−m).
3939
double wheelMaxTorque;
4040

4141
/// The Coefficient of Friction (CoF) of the wheels.
@@ -97,22 +97,22 @@ class TRAJOPT_DLLEXPORT DifferentialTrajectorySample {
9797
/// The heading.
9898
double heading = 0.0;
9999

100-
/// The left wheel velocity.
100+
/// The left wheel's velocity.
101101
double velocityL = 0.0;
102102

103-
/// The right wheel velocity.
103+
/// The right wheel's velocity.
104104
double velocityR = 0.0;
105105

106-
/// The left wheel acceleration.
106+
/// The left wheel's acceleration.
107107
double accelerationL = 0.0;
108108

109-
/// The right wheel acceleration.
109+
/// The right wheel's acceleration.
110110
double accelerationR = 0.0;
111111

112-
/// The left wheel force.
112+
/// The left wheel's force.
113113
double forceL = 0.0;
114114

115-
/// The right wheel force.
115+
/// The right wheel's force.
116116
double forceR = 0.0;
117117

118118
DifferentialTrajectorySample() = default;
@@ -152,15 +152,15 @@ class TRAJOPT_DLLEXPORT DifferentialTrajectorySample {
152152
*/
153153
class TRAJOPT_DLLEXPORT DifferentialTrajectory {
154154
public:
155-
/// Trajectory samples.
155+
/// The samples that make up the trajectory.
156156
std::vector<DifferentialTrajectorySample> samples;
157157

158158
DifferentialTrajectory() = default;
159159

160160
/**
161161
* Construct a DifferentialTrajectory from samples.
162162
*
163-
* @param samples The samples.
163+
* @param samples The samples that make up the trajectory.
164164
*/
165165
explicit DifferentialTrajectory(
166166
std::vector<DifferentialTrajectorySample> samples)

trajoptlib/include/trajopt/SwerveTrajectoryGenerator.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,13 @@ struct TRAJOPT_DLLEXPORT SwerveDrivetrain {
2727
/// The moment of inertia of the robot about the origin (kg−m²).
2828
double moi;
2929

30-
/// Radius of wheel (m).
30+
/// Radius of the wheels (m).
3131
double wheelRadius;
3232

33-
/// Maximum angular velocity of wheel (rad/s).
33+
/// Maximum angular velocity of each wheel (rad/s).
3434
double wheelMaxAngularVelocity;
3535

36-
/// Maximum torque applied to wheel (N−m).
36+
/// Maximum torque applied to each wheel (N−m).
3737
double wheelMaxTorque;
3838

3939
/// The Coefficient of Friction (CoF) of the wheels.
@@ -173,15 +173,15 @@ class TRAJOPT_DLLEXPORT SwerveTrajectorySample {
173173
*/
174174
class TRAJOPT_DLLEXPORT SwerveTrajectory {
175175
public:
176-
/// Trajectory samples.
176+
/// The samples that make up the trajectory.
177177
std::vector<SwerveTrajectorySample> samples;
178178

179179
SwerveTrajectory() = default;
180180

181181
/**
182182
* Construct a SwerveTrajectory from samples.
183183
*
184-
* @param samples The samples.
184+
* @param samples The samples that make up the trajectory.
185185
*/
186186
explicit SwerveTrajectory(std::vector<SwerveTrajectorySample> samples)
187187
: samples{std::move(samples)} {}

trajoptlib/include/trajopt/path/PathBuilder.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ template <typename Drivetrain, typename Solution>
4242
class TRAJOPT_DLLEXPORT PathBuilder {
4343
public:
4444
/**
45-
* Set the Drivetrain object
45+
* Set the Drivetrain object.
4646
*
4747
* @param drivetrain the new drivetrain
4848
*/

trajoptlib/src/error.rs

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,27 +1,37 @@
11
use thiserror::Error;
22

33
#[derive(Debug, Error)]
4-
// messages taken from https://github.com/SleipnirGroup/Sleipnir/blob/main/include/sleipnir/optimization/SolverExitCondition.hpp#L47-L78
4+
/// Represents an error returned by Trajoptlib. Primarily exposes the Sleipnir [Solver Exit
5+
/// Condition](https://github.com/SleipnirGroup/Sleipnir/blob/main/include/sleipnir/optimization/SolverExitCondition.hpp#L47-L78)
56
pub enum TrajoptError {
67
#[error("The solver determined the problem to be overconstrained and gave up")]
8+
/// The solver determined the problem to be overconstrained and gave up
79
TooFewDOF,
810
#[error("The solver determined the problem to be locally infeasible and gave up")]
11+
/// The solver determined the problem to be locally infeasible and gave up
912
LocallyInfeasible,
1013
#[error("The solver failed to reach the desired tolerance, and feasibility restoration failed to converge")]
14+
/// The solver failed to reach the desired tolerance, and feasibility restoration failed to converge
1115
FeasibilityRestorationFailed,
1216
#[error("The solver encountered nonfinite initial cost or constraints and gave up")]
17+
/// The solver encountered nonfinite initial cost or constraints and gave up
1318
NonfiniteInitialCostOrConstraints,
1419
#[error("The solver encountered diverging primal iterates xₖ and/or sₖ and gave up")]
20+
/// The solver encountered diverging primal iterates xₖ and/or sₖ and gave up
1521
DivergingIterates,
1622
#[error(
1723
"The solver returned its solution so far after exceeding the maximum number of iterations"
1824
)]
25+
/// The solver returned its solution so far after exceeding the maximum number of iterations
1926
MaxIterationsExceeded,
2027
#[error("The solver returned its solution so far after exceeding the maximum elapsed wall clock time")]
28+
/// The solver returned its solution so far after exceeding the maximum elapsed wall clock time
2129
Timeout,
2230
#[error("The solver returned an unparsable error code: {0}")]
31+
/// The solver returned an unparsable error code
2332
Unparsable(Box<str>),
2433
#[error("Unknown error: {0:?}")]
34+
/// Unknown error type
2535
Unknown(i8),
2636
}
2737

0 commit comments

Comments
 (0)