Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[choreo] Add Lane Constraint to UI #845

Merged
merged 17 commits into from
Oct 7, 2024
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
107 changes: 92 additions & 15 deletions src-core/src/generation/transformers/constraints.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,10 @@ use trajoptlib::PathBuilder;

use crate::spec::trajectory::{ConstraintData, ConstraintIDX, ConstraintScope};

use super::{DifferentialGenerationTransformer, FeatureLockedTransformer, GenerationContext, SwerveGenerationTransformer};
use super::{
DifferentialGenerationTransformer, FeatureLockedTransformer, GenerationContext,
SwerveGenerationTransformer,
};

fn fix_scope(idx: usize, removed_idxs: &[usize]) -> usize {
let mut to_subtract: usize = 0;
Expand All @@ -16,7 +19,7 @@ fn fix_scope(idx: usize, removed_idxs: &[usize]) -> usize {

pub struct ConstraintSetter {
guess_points: Vec<usize>,
constraint_idx: Vec<ConstraintIDX<f64>>
constraint_idx: Vec<ConstraintIDX<f64>>,
}

impl ConstraintSetter {
Expand All @@ -26,7 +29,9 @@ impl ConstraintSetter {
let mut constraint_idx = Vec::<ConstraintIDX<f64>>::new();
let num_wpts = ctx.params.waypoints.len();

ctx.params.waypoints.iter()
ctx.params
.waypoints
.iter()
.enumerate()
.filter(|(_, w)| w.is_initial_guess && !w.fix_heading && !w.fix_translation)
.for_each(|(idx, _)| guess_points.push(idx));
Expand Down Expand Up @@ -64,7 +69,7 @@ impl ConstraintSetter {
from: fixed_from,
to: fixed_to,
data: constraint.data,
enabled: constraint.enabled
enabled: constraint.enabled,
});
}
}
Expand All @@ -73,7 +78,7 @@ impl ConstraintSetter {

FeatureLockedTransformer::always(Self {
guess_points,
constraint_idx
constraint_idx,
})
}
}
Expand All @@ -95,7 +100,7 @@ impl SwerveGenerationTransformer for ConstraintSetter {
flip,
} => match to_opt {
None => builder.wpt_point_at(from, x, y, tolerance, flip),
Some(to) => builder.sgmt_point_at(from, to, x, y, tolerance, flip)
Some(to) => builder.sgmt_point_at(from, to, x, y, tolerance, flip),
},
ConstraintData::MaxVelocity { max } => match to_opt {
None => builder.wpt_linear_velocity_max_magnitude(from, max),
Expand All @@ -114,7 +119,7 @@ impl SwerveGenerationTransformer for ConstraintSetter {
builder.wpt_linear_velocity_max_magnitude(from, 0.0f64);
builder.wpt_angular_velocity_max_magnitude(from, 0.0f64);
}
},
}
ConstraintData::KeepInCircle { x, y, r } => match to_opt {
None => builder.wpt_keep_in_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_in_circle(from, to, x, y, r),
Expand All @@ -127,11 +132,45 @@ impl SwerveGenerationTransformer for ConstraintSetter {
Some(to) => builder.sgmt_keep_in_polygon(from, to, xs, ys),
}
}
ConstraintData::KeepOutCircle { x, y, r } => {
ConstraintData::KeepInLane {
below_start_x,
below_start_y,
below_end_x,
below_end_y,
above_start_x,
above_start_y,
above_end_x,
above_end_y,
} => {
let center_line_start_x = (below_start_x + above_start_x) / 2.0;
let center_line_start_y = (below_start_y + above_start_y) / 2.0;
let center_line_end_x = (below_end_x + above_end_x) / 2.0;
let center_line_end_y = (below_end_y + above_end_y) / 2.0;
let tolerance = 1.0; // TODO how
calcmogul marked this conversation as resolved.
Show resolved Hide resolved

match to_opt {
None => builder.wpt_keep_out_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_out_circle(from, to, x, y, r),
None => builder.wpt_keep_in_lane(
from,
center_line_start_x,
center_line_start_y,
center_line_end_x,
center_line_end_y,
tolerance,
),
Some(to) => builder.sgmt_keep_in_lane(
from,
to,
center_line_start_x,
center_line_start_y,
center_line_end_x,
center_line_end_y,
tolerance,
),
}
}
ConstraintData::KeepOutCircle { x, y, r } => match to_opt {
None => builder.wpt_keep_out_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_out_circle(from, to, x, y, r),
},
};
}
Expand All @@ -152,7 +191,11 @@ impl DifferentialGenerationTransformer for ConstraintSetter {
y,
tolerance,
flip,
} => if to_opt.is_none() { builder.wpt_point_at(from, x, y, tolerance, flip) },
} => {
if to_opt.is_none() {
builder.wpt_point_at(from, x, y, tolerance, flip)
}
}
ConstraintData::MaxVelocity { max } => match to_opt {
None => builder.wpt_linear_velocity_max_magnitude(from, max),
Some(to) => builder.sgmt_linear_velocity_max_magnitude(from, to, max),
Expand All @@ -170,7 +213,7 @@ impl DifferentialGenerationTransformer for ConstraintSetter {
builder.wpt_linear_velocity_max_magnitude(from, 0.0f64);
builder.wpt_angular_velocity_max_magnitude(from, 0.0f64);
}
},
}
ConstraintData::KeepInCircle { x, y, r } => match to_opt {
None => builder.wpt_keep_in_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_in_circle(from, to, x, y, r),
Expand All @@ -183,11 +226,45 @@ impl DifferentialGenerationTransformer for ConstraintSetter {
Some(to) => builder.sgmt_keep_in_polygon(from, to, xs, ys),
}
}
ConstraintData::KeepOutCircle { x, y, r } => {
ConstraintData::KeepInLane {
below_start_x,
below_start_y,
below_end_x,
below_end_y,
above_start_x,
above_start_y,
above_end_x,
above_end_y,
} => {
let center_line_start_x = (below_start_x + above_start_x) / 2.0;
let center_line_start_y = (below_start_y + above_start_y) / 2.0;
let center_line_end_x = (below_end_x + above_end_x) / 2.0;
let center_line_end_y = (below_end_y + above_end_y) / 2.0;
let tolerance = 1.0; // TODO how
calcmogul marked this conversation as resolved.
Show resolved Hide resolved

match to_opt {
None => builder.wpt_keep_out_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_out_circle(from, to, x, y, r),
None => builder.wpt_keep_in_lane(
from,
center_line_start_x,
center_line_start_y,
center_line_end_x,
center_line_end_y,
tolerance,
),
Some(to) => builder.sgmt_keep_in_lane(
from,
to,
center_line_start_x,
center_line_start_y,
center_line_end_x,
center_line_end_y,
tolerance,
),
}
}
ConstraintData::KeepOutCircle { x, y, r } => match to_opt {
None => builder.wpt_keep_out_circle(from, x, y, r),
Some(to) => builder.sgmt_keep_out_circle(from, to, x, y, r),
},
};
}
Expand Down
30 changes: 30 additions & 0 deletions src-core/src/spec/trajectory.rs
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,17 @@ pub enum ConstraintData<T: SnapshottableType> {
KeepInCircle { x: T, y: T, r: T },
/// A constraint to contain the bumpers within a rectangular region of the field
KeepInRectangle { x: T, y: T, w: T, h: T },
/// A constraint to contain the bumpers within two line
KeepInLane {
below_start_x: T,
below_start_y: T,
below_end_x: T,
below_end_y: T,
above_start_x: T,
above_start_y: T,
above_end_x: T,
above_end_y: T,
},
/// A constraint to contain the bumpers outside a circlular region of the field
KeepOutCircle { x: T, y: T, r: T },
}
Expand Down Expand Up @@ -195,6 +206,25 @@ impl<T: SnapshottableType> ConstraintData<T> {
w: w.snapshot(),
h: h.snapshot(),
},
ConstraintData::KeepInLane {
below_start_x,
below_start_y,
below_end_x,
below_end_y,
above_start_x,
above_start_y,
above_end_x,
above_end_y,
} => ConstraintData::KeepInLane {
below_start_x: below_start_x.snapshot(),
below_start_y: below_start_y.snapshot(),
below_end_x: below_end_x.snapshot(),
below_end_y: below_end_y.snapshot(),
above_start_x: above_start_x.snapshot(),
above_start_y: above_start_y.snapshot(),
above_end_x: above_end_x.snapshot(),
above_end_y: above_end_y.snapshot(),
},
ConstraintData::KeepOutCircle { x, y, r } => ConstraintData::KeepOutCircle {
x: x.snapshot(),
y: y.snapshot(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ import KeepInCircleOverlay from "./KeepInCircleOverlay";
import KeepInRectangleOverlay from "./KeepInRectangleOverlay";
import PointAtOverlay from "./PointAtOverlay";
import KeepOutCircleOverlay from "./KeepOutCircleOverlay";
import KeepInLaneOverlay from "./KeepInLaneOverlay";

const overlays = {
PointAt: (
Expand Down Expand Up @@ -42,6 +43,13 @@ const overlays = {
lineColor={lineColor}
></KeepInRectangleOverlay>
),
KeepInLane: (constraint: IConstraintStoreKeyed<"KeepInLane">) => (
<KeepInLaneOverlay
data={constraint.data}
start={constraint.getStartWaypoint()}
end={constraint.getEndWaypoint()}
></KeepInLaneOverlay>
),
KeepOutCircle: (
constraint: IConstraintStoreKeyed<"KeepOutCircle">,
lineColor: string
Expand Down
Loading
Loading