Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
[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 <spacey-sooty@proton.me>
spacey-sooty committed Nov 25, 2024
1 parent c3130d1 commit 960897f
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
@@ -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
@@ -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.
@@ -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;
@@ -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)
10 changes: 5 additions & 5 deletions trajoptlib/include/trajopt/SwerveTrajectoryGenerator.hpp
Original file line number Diff line number Diff line change
@@ -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.
@@ -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)} {}
2 changes: 1 addition & 1 deletion trajoptlib/include/trajopt/path/PathBuilder.hpp
Original file line number Diff line number Diff line change
@@ -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
*/
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),
}

177 changes: 150 additions & 27 deletions trajoptlib/src/lib.rs
Original file line number Diff line number Diff line change
@@ -1,77 +1,133 @@
#![deny(missing_docs)]
#![doc = include_str!("../README.md")]

#[cxx::bridge(namespace = "trajopt::rsffi")]
mod ffi {
#[derive(Debug, Deserialize, Serialize, Clone)]
/// Represents a translation in 2D space.
struct Translation2d {
/// The x component of the translation.
x: f64,
/// The y component of the translation.
y: f64,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
struct SwerveDrivetrain {
mass: f64,
moi: f64,
wheel_radius: f64,
wheel_max_angular_velocity: f64,
wheel_max_torque: f64,
wheel_cof: f64,
modules: Vec<Translation2d>,
/// Represents a 2D pose with translation and rotation.
struct Pose2d {
/// The x component of the translational component of the pose.
x: f64,
/// The y component of the translational component of the pose.
y: f64,
/// The rotational component of the pose.
heading: f64,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
struct DifferentialDrivetrain {
/// A swerve drivetrain physical model.
struct SwerveDrivetrain {
/// The mass of the robot (kg).
mass: f64,
/// The moment of inertia of the robot about the origin (kg−m²).
moi: f64,
/// Radius of the wheels (m).
wheel_radius: f64,
/// Maximum angular velocity of each wheel (rad/s).
wheel_max_angular_velocity: f64,
/// Maximum torque applied to each wheel (N−m).
wheel_max_torque: f64,
/// The Coefficient of Friction (CoF) of the wheels.
wheel_cof: f64,
trackwidth: f64,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
struct Pose2d {
x: f64,
y: f64,
heading: f64,
/// Translation of each swerve module from the origin of the robot coordinate
/// system to the center of the module (m). There's usually one in each
/// corner.
modules: Vec<Translation2d>,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
/// Swerve trajectory sample.
struct SwerveTrajectorySample {
/// The timestamp.
timestamp: f64,
/// The x coordinate.
x: f64,
/// The y coordinate.
y: f64,
/// The heading.
heading: f64,
/// The velocity's x component.
velocity_x: f64,
/// The velocity's y component.
velocity_y: f64,
/// The angular velocity.
angular_velocity: f64,
/// The acceleration's x component.
acceleration_x: f64,
/// The acceleration's y component.
acceleration_y: f64,
/// The angular acceleration.
angular_acceleration: f64,
/// The force on each module in the X direction.
module_forces_x: Vec<f64>,
/// The force on each module in the Y direction.
module_forces_y: Vec<f64>,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
/// Swerve trajectory.
struct SwerveTrajectory {
/// The samples that make up the trajectory.
samples: Vec<SwerveTrajectorySample>,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
/// A differential drivetrain physical model.
struct DifferentialDrivetrain {
/// The mass of the robot (kg).
mass: f64,
/// The moment of inertia of the robot about the origin (kg−m²).
moi: f64,
/// Radius of the wheels (m).
wheel_radius: f64,
/// Maximum angular velocity of the wheels (rad/s).
wheel_max_angular_velocity: f64,
/// Maximum torque applied to the wheels (N−m).
wheel_max_torque: f64,
/// The Coefficient of Friction (CoF) of the wheels.
wheel_cof: f64,
/// Distance between the two driverails (m).
trackwidth: f64,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
/// Differential trajectory sample.
struct DifferentialTrajectorySample {
/// The timestamp.
timestamp: f64,
/// The x coordinate.
x: f64,
/// The y coordinate.
y: f64,
/// The heading.
heading: f64,
/// The left wheel's velocity.
velocity_l: f64,
/// The right wheel's velocity.
velocity_r: f64,
/// The left wheel's acceleration.
acceleration_l: f64,
/// The right wheel's acceleration.
acceleration_r: f64,
/// The left wheel's force.
force_l: f64,
/// The right wheel's force.
force_r: f64,
}

#[derive(Debug, Deserialize, Serialize, Clone)]
/// Differential trajectory.
struct DifferentialTrajectory {
/// The samples that make up the trajectory.
samples: Vec<DifferentialTrajectorySample>,
}

@@ -501,6 +557,9 @@ mod ffi {
}
}


/// This trajectory generator class contains functions to generate
/// time-optimal trajectories for several drivetrain types.
pub struct SwerveTrajectoryGenerator {
generator: cxx::UniquePtr<crate::ffi::SwerveTrajectoryGenerator>,
}
@@ -512,16 +571,25 @@ impl Default for SwerveTrajectoryGenerator {
}

impl SwerveTrajectoryGenerator {
/// Construct a new swerve trajectory optimization problem.
pub fn new() -> SwerveTrajectoryGenerator {
SwerveTrajectoryGenerator {
generator: crate::ffi::swerve_trajectory_generator_new(),
}
}

/// Set the Drivetrain object.
pub fn set_drivetrain(&mut self, drivetrain: &crate::ffi::SwerveDrivetrain) {
crate::ffi::SwerveTrajectoryGenerator::set_drivetrain(self.generator.pin_mut(), drivetrain);
}

/// Add a rectangular bumper to a list used when applying
/// keep-out constraints.
///
/// * `front` - Distance in meters from center to front bumper edge
/// * `left` - Distance in meters from center to left bumper edge
/// * `right` - Distance in meters from center to right bumper edge
/// * `back` - Distance in meters from center to back bumper edge
pub fn set_bumpers(&mut self, front: f64, left: f64, right: f64, back: f64) {
crate::ffi::SwerveTrajectoryGenerator::set_bumpers(
self.generator.pin_mut(),
@@ -532,6 +600,11 @@ impl SwerveTrajectoryGenerator {
);
}

/// If using a discrete algorithm, specify the number of discrete
/// samples for every segment of the trajectory
///
/// * `counts` - the sequence of control interval counts per segment, length
/// is number of waypoints - 1
pub fn set_control_interval_counts(&mut self, counts: Vec<usize>) {
crate::ffi::SwerveTrajectoryGenerator::set_control_interval_counts(
self.generator.pin_mut(),
@@ -541,6 +614,15 @@ impl SwerveTrajectoryGenerator {

// Constraints with waypoint scope

/// Create a pose waypoint constraint on the waypoint at the provided
/// index, and add an initial guess with the same pose This specifies that the
/// position and heading of the robot at the waypoint must be fixed at the
/// values provided.
///
/// * `index` - index of the pose waypoint
/// * `x` - the x
/// * `y` - the y
/// * `heading` - the heading
pub fn pose_wpt(&mut self, index: usize, x: f64, y: f64, heading: f64) {
crate::ffi::SwerveTrajectoryGenerator::pose_wpt(
self.generator.pin_mut(),
@@ -551,6 +633,15 @@ impl SwerveTrajectoryGenerator {
);
}

/// Create a translation waypoint constraint on the waypoint at the
/// provided index, and add an initial guess point with the same translation.
/// This specifies that the position of the robot at the waypoint must be fixed
/// at the value provided.
///
/// * `index` - index of the pose waypoint
/// * `x` - the x
/// * `y` - the y
/// * `headingGuess` - optionally, an initial guess of the heading
pub fn translation_wpt(&mut self, index: usize, x: f64, y: f64, heading_guess: f64) {
crate::ffi::SwerveTrajectoryGenerator::translation_wpt(
self.generator.pin_mut(),
@@ -856,10 +947,9 @@ impl SwerveTrajectoryGenerator {
)
}

///
/// Add a callback that will be called on each iteration of the solver.
///
/// * callback: a `fn` (not a closure) to be executed. The callback's first
/// * `callback` - a `fn` (not a closure) to be executed. The callback's first
/// parameter will be a `trajopt::SwerveTrajectory`, and the second
/// parameter will be an `i64` equal to the handle passed in `generate()`
///
@@ -868,12 +958,11 @@ impl SwerveTrajectoryGenerator {
crate::ffi::SwerveTrajectoryGenerator::add_callback(self.generator.pin_mut(), callback);
}

///
/// Generate the trajectory;
///
/// * diagnostics: If true, prints per-iteration details of the solver to
/// * `diagnostics` - If true, prints per-iteration details of the solver to
/// stdout.
/// * handle: A number used to identify results from this generation in the
/// * `handle` - A number used to identify results from this generation in the
/// `add_callback` callback. If `add_callback` has not been called, this
/// value has no significance.
///
@@ -897,6 +986,8 @@ impl SwerveTrajectoryGenerator {
}
}

/// This trajectory generator class contains functions to generate
/// time-optimal trajectories for differential drivetrain types.
pub struct DifferentialTrajectoryGenerator {
generator: cxx::UniquePtr<crate::ffi::DifferentialTrajectoryGenerator>,
}
@@ -908,19 +999,28 @@ impl Default for DifferentialTrajectoryGenerator {
}

impl DifferentialTrajectoryGenerator {
/// Construct a new differential trajectory optimization problem.
pub fn new() -> DifferentialTrajectoryGenerator {
DifferentialTrajectoryGenerator {
generator: crate::ffi::differential_trajectory_generator_new(),
}
}

/// Set the Drivetrain object.
pub fn set_drivetrain(&mut self, drivetrain: &crate::ffi::DifferentialDrivetrain) {
crate::ffi::DifferentialTrajectoryGenerator::set_drivetrain(
self.generator.pin_mut(),
drivetrain,
);
}

/// Add a rectangular bumper to a list used when applying
/// keep-out constraints.
///
/// * `front` - Distance in meters from center to front bumper edge
/// * `left` - Distance in meters from center to left bumper edge
/// * `right` - Distance in meters from center to right bumper edge
/// * `back` - Distance in meters from center to back bumper edge
pub fn set_bumpers(&mut self, front: f64, left: f64, right: f64, back: f64) {
crate::ffi::DifferentialTrajectoryGenerator::set_bumpers(
self.generator.pin_mut(),
@@ -931,6 +1031,11 @@ impl DifferentialTrajectoryGenerator {
);
}

/// If using a discrete algorithm, specify the number of discrete
/// samples for every segment of the trajectory
///
/// * `counts` - the sequence of control interval counts per segment, length
/// is number of waypoints - 1
pub fn set_control_interval_counts(&mut self, counts: Vec<usize>) {
crate::ffi::DifferentialTrajectoryGenerator::set_control_interval_counts(
self.generator.pin_mut(),
@@ -940,6 +1045,15 @@ impl DifferentialTrajectoryGenerator {

// Pose constraints

/// Create a pose waypoint constraint on the waypoint at the provided
/// index, and add an initial guess with the same pose This specifies that the
/// position and heading of the robot at the waypoint must be fixed at the
/// values provided.
///
/// * `index` - index of the pose waypoint
/// * `x` - the x
/// * `y` - the y
/// * `heading` - the heading
pub fn pose_wpt(&mut self, index: usize, x: f64, y: f64, heading: f64) {
crate::ffi::DifferentialTrajectoryGenerator::pose_wpt(
self.generator.pin_mut(),
@@ -950,6 +1064,15 @@ impl DifferentialTrajectoryGenerator {
);
}

/// Create a translation waypoint constraint on the waypoint at the
/// provided index, and add an initial guess point with the same translation.
/// This specifies that the position of the robot at the waypoint must be fixed
/// at the value provided.
///
/// * `index` - index of the pose waypoint
/// * `x` - the x
/// * `y` - the y
/// * `headingGuess` - optionally, an initial guess of the heading
pub fn translation_wpt(&mut self, index: usize, x: f64, y: f64, heading_guess: f64) {
crate::ffi::DifferentialTrajectoryGenerator::translation_wpt(
self.generator.pin_mut(),
@@ -1235,10 +1358,9 @@ impl DifferentialTrajectoryGenerator {
);
}

///
/// Add a callback that will be called on each iteration of the solver.
///
/// * callback: a `fn` (not a closure) to be executed. The callback's first
/// * `callback` - a `fn` (not a closure) to be executed. The callback's first
/// parameter will be a `trajopt::DifferentialTrajectory`, and the second
/// parameter will be an `i64` equal to the handle passed in `generate()`
///
@@ -1250,12 +1372,11 @@ impl DifferentialTrajectoryGenerator {
);
}

///
/// Generate the trajectory;
///
/// * diagnostics: If true, prints per-iteration details of the solver to
/// * `diagnostics` - If true, prints per-iteration details of the solver to
/// stdout.
/// * handle: A number used to identify results from this generation in the
/// * `handle` - A number used to identify results from this generation in the
/// `add_callback` callback. If `add_callback` has not been called, this
/// value has no significance.
///
@@ -1280,6 +1401,7 @@ impl DifferentialTrajectoryGenerator {
}
}

/// Cancels all running generations.
pub fn cancel_all() {
crate::ffi::cancel_all();
}
@@ -1294,4 +1416,5 @@ pub use ffi::SwerveTrajectory;
pub use ffi::SwerveTrajectorySample;
pub use ffi::Translation2d;

/// Solver error types.
pub mod error;

0 comments on commit 960897f

Please sign in to comment.