Skip to content

Commit

Permalink
[trajoptlib] Rename obstacle to keep-out region (#935)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Nov 20, 2024
1 parent afab0e7 commit adf9525
Show file tree
Hide file tree
Showing 9 changed files with 51 additions and 71 deletions.
22 changes: 12 additions & 10 deletions src/document/ConstraintDefinitions.tsx
Original file line number Diff line number Diff line change
Expand Up @@ -192,19 +192,19 @@ export const ConstraintDefinitions: defs = {
properties: {
x: {
name: "X",
description: "The x coordinate of the center of the keep in zone",
description: "The x coordinate of the center of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
y: {
name: "Y",
description: "The y coordinate of the center of the keep in zone",
description: "The y coordinate of the center of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
r: {
name: "R",
description: "The radius of the keep in zone",
description: "The radius of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "1 m", val: 1 }
}
Expand All @@ -221,25 +221,27 @@ export const ConstraintDefinitions: defs = {
properties: {
x: {
name: "X",
description: "The x coordinate of the bottom left of the keep in zone",
description:
"The x coordinate of the bottom left of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
y: {
name: "Y",
description: "The y coordinate of the bottom left of the keep in zone",
description:
"The y coordinate of the bottom left of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
w: {
name: "W",
description: "The width of the keep in zone",
description: "The width of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "1 m", val: 1 }
},
h: {
name: "H",
description: "The height of the keep in zone",
description: "The height of the keep-in region",
dimension: Dimensions.Length,
defaultVal: { exp: "1 m", val: 1 }
}
Expand Down Expand Up @@ -273,19 +275,19 @@ export const ConstraintDefinitions: defs = {
properties: {
x: {
name: "X",
description: "The x coordinate of the center of the keep out zone",
description: "The x coordinate of the center of the keep-out region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
y: {
name: "Y",
description: "The y coordinate of the center of the keep out zone",
description: "The y coordinate of the center of the keep-out region",
dimension: Dimensions.Length,
defaultVal: { exp: "0 m", val: 0 }
},
r: {
name: "R",
description: "The radius of the keep out zone",
description: "The radius of the keep-out region",
dimension: Dimensions.Length,
defaultVal: { exp: "1 m", val: 1 }
}
Expand Down
2 changes: 1 addition & 1 deletion trajoptlib/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ Trajectory optimization works by mathematically formulating the problem of trave

* Currently only supports swerve drives with arbitrary module configurations
* Position and velocity constraints at each waypoint
* Circle and polygon obstacle avoidance
* Keep-out circle and polygons
* Custom physical constraints of robot
* Custom bumper shape

Expand Down
12 changes: 6 additions & 6 deletions trajoptlib/examples/Differential/src/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,26 +86,26 @@ int main() {
auto solution = generator.Generate(true);
}

// Example 5: Differential, circle obstacle
// Example 5: Differential, keep-out circle
{
trajopt::DifferentialPathBuilder path;
path.SetDrivetrain(differentialDrivetrain);
path.PoseWpt(0, 0.0, 0.0, 0.0);
trajopt::Obstacle obstacle{// Radius of 0.1
.safetyDistance = 0.1,
.points = {{0.5, 0.5}}};
trajopt::KeepOutRegion keepOut{// Radius of 0.1
.safetyDistance = 0.1,
.points = {{0.5, 0.5}}};
for (size_t i = 0; i < path.GetBumpers().at(0).points.size(); i++) {
path.SgmtConstraint(0, 1,
trajopt::PointPointMinConstraint{
path.GetBumpers().at(0).points.at(i),
obstacle.points.at(0), obstacle.safetyDistance});
keepOut.points.at(0), keepOut.safetyDistance});
path.SgmtConstraint(
0, 1,
trajopt::LinePointConstraint{
path.GetBumpers().at(0).points.at(i),
path.GetBumpers().at(0).points.at(
(i + 1) % path.GetBumpers().at(0).points.size()),
obstacle.points.at(0), obstacle.safetyDistance});
keepOut.points.at(0), keepOut.safetyDistance});
}
path.PoseWpt(1, 1.0, 0.0, 0.0);
path.WptConstraint(0, zeroLinearVelocity);
Expand Down
12 changes: 6 additions & 6 deletions trajoptlib/examples/Swerve/src/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,26 +86,26 @@ int main() {
auto solution = generator.Generate(true);
}

// Example 5: Swerve, circle obstacle
// Example 5: Swerve, keep-out circle
{
trajopt::SwervePathBuilder path;
path.SetDrivetrain(swerveDrivetrain);
path.PoseWpt(0, 0.0, 0.0, 0.0);
trajopt::Obstacle obstacle{// Radius of 0.1
.safetyDistance = 0.1,
.points = {{0.5, 0.5}}};
trajopt::KeepOutRegion keepOut{// Radius of 0.1
.safetyDistance = 0.1,
.points = {{0.5, 0.5}}};
for (size_t i = 0; i < path.GetBumpers().at(0).points.size(); i++) {
path.SgmtConstraint(0, 1,
trajopt::PointPointMinConstraint{
path.GetBumpers().at(0).points.at(i),
obstacle.points.at(0), obstacle.safetyDistance});
keepOut.points.at(0), keepOut.safetyDistance});
path.SgmtConstraint(
0, 1,
trajopt::LinePointConstraint{
path.GetBumpers().at(0).points.at(i),
path.GetBumpers().at(0).points.at(
(i + 1) % path.GetBumpers().at(0).points.size()),
obstacle.points.at(0), obstacle.safetyDistance});
keepOut.points.at(0), keepOut.safetyDistance});
}

path.PoseWpt(1, 1.0, 0.0, 0.0);
Expand Down
11 changes: 0 additions & 11 deletions trajoptlib/include/trajopt/obstacle/Bumpers.hpp

This file was deleted.

26 changes: 0 additions & 26 deletions trajoptlib/include/trajopt/obstacle/Obstacle.hpp

This file was deleted.

33 changes: 24 additions & 9 deletions trajoptlib/include/trajopt/path/PathBuilder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,28 @@
#include <vector>

#include "trajopt/constraint/Constraint.hpp"
#include "trajopt/obstacle/Bumpers.hpp"
#include "trajopt/geometry/Translation2.hpp"
#include "trajopt/path/Path.hpp"
#include "trajopt/util/GenerateLinearInitialGuess.hpp"
#include "trajopt/util/SymbolExports.hpp"

namespace trajopt {

/**
* Represents a physical keep-out region that the robot must avoid by a certain
* distance. Arbitrary polygons can be expressed with this class, and keep-out
* circles can also be created by only using one point with a safety distance.
*
* Keep-out points must be wound either clockwise or counterclockwise.
*/
struct TRAJOPT_DLLEXPORT KeepOutRegion {
/// Minimum distance from the keep-out region the robot must maintain.
double safetyDistance;

/// The list of points that make up this keep-out region.
std::vector<Translation2d> points;
};

/**
* Path builder.
*
Expand All @@ -37,27 +52,27 @@ class TRAJOPT_DLLEXPORT PathBuilder {

/**
* Add a rectangular bumper to a list used when applying
* obstacle constraints.
* keep-out constraints.
*
* @param front Distance in meters from center to front bumper edge
* @param left Distance in meters from center to left bumper edge
* @param right Distance in meters from center to right bumper edge
* @param back Distance in meters from center to back bumper edge
*/
void SetBumpers(double front, double left, double right, double back) {
bumpers.emplace_back(trajopt::Bumpers{.safetyDistance = 0.01,
.points = {{+front, +left},
{-back, +left},
{-back, -right},
{+front, -right}}});
bumpers.emplace_back(trajopt::KeepOutRegion{.safetyDistance = 0.01,
.points = {{+front, +left},
{-back, +left},
{-back, -right},
{+front, -right}}});
}

/**
* Get all bumpers currently added to the path builder
*
* @return a list of bumpers applied to the builder.
*/
std::vector<Bumpers>& GetBumpers() { return bumpers; }
std::vector<KeepOutRegion>& GetBumpers() { return bumpers; }

/**
* If using a discrete algorithm, specify the number of discrete
Expand Down Expand Up @@ -211,7 +226,7 @@ class TRAJOPT_DLLEXPORT PathBuilder {
Path<Drivetrain, Solution> path;

/// The list of bumpers.
std::vector<Bumpers> bumpers;
std::vector<KeepOutRegion> bumpers;

/// The initial guess points.
std::vector<std::vector<Pose2d>> initialGuessPoints;
Expand Down
2 changes: 1 addition & 1 deletion trajoptlib/src/DifferentialTrajectoryGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ DifferentialTrajectoryGenerator::DifferentialTrajectoryGenerator(
for (size_t sgmtIndex = 0; sgmtIndex < sgmtCnt; ++sgmtIndex) {
dts.emplace_back(problem.DecisionVariable());

// Prevent drivetrain tunneling through obstacles
// Prevent drivetrain tunneling through keep-out regions
problem.SubjectTo(dts.at(sgmtIndex) * path.drivetrain.wheelRadius *
path.drivetrain.wheelMaxAngularVelocity <=
minWidth);
Expand Down
2 changes: 1 addition & 1 deletion trajoptlib/src/SwerveTrajectoryGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ SwerveTrajectoryGenerator::SwerveTrajectoryGenerator(
for (size_t sgmtIndex = 0; sgmtIndex < sgmtCnt; ++sgmtIndex) {
dts.emplace_back(problem.DecisionVariable());

// Prevent drivetrain tunneling through obstacles
// Prevent drivetrain tunneling through keep-out regions
problem.SubjectTo(dts.at(sgmtIndex) * path.drivetrain.wheelRadius *
path.drivetrain.wheelMaxAngularVelocity <=
minWidth);
Expand Down

0 comments on commit adf9525

Please sign in to comment.