Skip to content

Commit

Permalink
Merge branch 'main' into always-visible-field-overlays
Browse files Browse the repository at this point in the history
  • Loading branch information
shueja authored Nov 14, 2024
2 parents 693cbce + a5ddf2d commit 34e4a48
Show file tree
Hide file tree
Showing 36 changed files with 434 additions and 298 deletions.
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,14 @@
"cargo", "clippy", "--target-dir", "./target/clippy"
],
"files.associations": {
"*.py": "python",
"*.traj": "json",
"vector": "cpp",
"array": "cpp",
"deque": "cpp",
"map": "cpp",
"unordered_map": "cpp",
"xstring": "cpp"
"type_traits": "cpp"
},
"java.configuration.updateBuildConfiguration": "interactive",
}
12 changes: 6 additions & 6 deletions choreolib/src/main/java/choreo/Choreo.java
Original file line number Diff line number Diff line change
Expand Up @@ -296,25 +296,25 @@ public void clear() {
* Create a factory that can be used to create {@link AutoRoutine} and {@link AutoTrajectory}.
*
* @param <SampleType> The type of samples in the trajectory.
* @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
* Command}s.
* @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
* robot.
* @param controller A {@link BiConsumer} to follow the current {@link Trajectory}&lt;{@link
* SampleType}&gt;.
* @param mirrorTrajectory If this returns true, the path will be mirrored to the opposite side,
* while keeping the same coordinate system origin. This will be called every loop during the
* command.
* @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
* Command}s.
* @param bindings Universal trajectory event bindings.
* @return An {@link AutoFactory} that can be used to create {@link AutoRoutine} and {@link
* AutoTrajectory}.
* @see AutoChooser using this factory with AutoChooser to generate auto routines.
*/
public static <SampleType extends TrajectorySample<SampleType>> AutoFactory createAutoFactory(
Subsystem driveSubsystem,
Supplier<Pose2d> poseSupplier,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
Subsystem driveSubsystem,
AutoBindings bindings) {
return new AutoFactory(
requireNonNullParam(poseSupplier, "poseSupplier", "Choreo.createAutoFactory"),
Expand All @@ -329,15 +329,15 @@ public static <SampleType extends TrajectorySample<SampleType>> AutoFactory crea
* Create a factory that can be used to create {@link AutoRoutine} and {@link AutoTrajectory}.
*
* @param <SampleType> The type of samples in the trajectory.
* @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
* Command}s.
* @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
* robot.
* @param controller A {@link BiConsumer} to follow the current {@link Trajectory}&lt;{@link
* SampleType}&gt;.
* @param mirrorTrajectory If this returns true, the path will be mirrored to the opposite side,
* while keeping the same coordinate system origin. This will be called every loop during the
* command.
* @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
* Command}s.
* @param bindings Universal trajectory event bindings.
* @param trajectoryLogger A {@link TrajectoryLogger} to log {@link Trajectory} as they start and
* finish.
Expand All @@ -346,10 +346,10 @@ public static <SampleType extends TrajectorySample<SampleType>> AutoFactory crea
* @see AutoChooser using this factory with AutoChooser to generate auto routines.
*/
public static <SampleType extends TrajectorySample<SampleType>> AutoFactory createAutoFactory(
Subsystem driveSubsystem,
Supplier<Pose2d> poseSupplier,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
Subsystem driveSubsystem,
AutoBindings bindings,
TrajectoryLogger<SampleType> trajectoryLogger) {
return new AutoFactory(
Expand Down
5 changes: 5 additions & 0 deletions choreolib/src/main/java/choreo/trajectory/ProjectFile.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,9 @@ public static class Config {
/** The maximum torque of the robot. (N-m) */
public final Expression tmax;

/** The Coefficient of Friction (CoF) of the wheels. */
public final Expression cof;

/** The bumpers of the robot. */
public final Bumpers bumper;

Expand All @@ -96,6 +99,7 @@ public static class Config {
Expression wheelRadius,
Expression vmax,
Expression tmax,
Expression cof,
Bumpers bumper,
Expression differentialTrackWidth) {
this.frontLeft = frontLeft;
Expand All @@ -106,6 +110,7 @@ public static class Config {
this.wheelRadius = wheelRadius;
this.vmax = vmax;
this.tmax = tmax;
this.cof = cof;
this.bumper = bumper;
this.differentialTrackWidth = differentialTrackWidth;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include "choreo/Choreo.h"
#include "choreo/trajectory/TrajectorySample.h"

using namespace choreo;
namespace choreo {

units::second_t DifferentialSample::GetTimestamp() const {
return timestamp;
Expand Down Expand Up @@ -53,8 +53,7 @@ DifferentialSample DifferentialSample::Interpolate(
};
}

void choreo::to_json(wpi::json& json,
const DifferentialSample& trajectorySample) {
void to_json(wpi::json& json, const DifferentialSample& trajectorySample) {
json = wpi::json{{"t", trajectorySample.timestamp.value()},
{"x", trajectorySample.x.value()},
{"y", trajectorySample.y.value()},
Expand All @@ -67,8 +66,7 @@ void choreo::to_json(wpi::json& json,
{"fr", trajectorySample.fr.value()}};
}

void choreo::from_json(const wpi::json& json,
DifferentialSample& trajectorySample) {
void from_json(const wpi::json& json, DifferentialSample& trajectorySample) {
trajectorySample.timestamp = units::second_t{json.at("t").get<double>()};
trajectorySample.x = units::meter_t{json.at("x").get<double>()};
trajectorySample.y = units::meter_t{json.at("y").get<double>()};
Expand All @@ -82,3 +80,5 @@ void choreo::from_json(const wpi::json& json,
trajectorySample.fl = units::newton_t{json.at("fl").get<double>()};
trajectorySample.fr = units::newton_t{json.at("fr").get<double>()};
}

} // namespace choreo
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ void choreo::to_json(wpi::json& json, const Config& config) {
{"radius", config.wheelRadius},
{"vmax", config.vmax},
{"tmax", config.tmax},
{"cof", config.cof},
{"bumper", config.bumpers},
{"differentialTrackWidth", config.differentialTrackWidth}};
}
Expand All @@ -82,6 +83,7 @@ void choreo::from_json(const wpi::json& json, Config& config) {
json.at("radius").get_to(config.wheelRadius);
json.at("vmax").get_to(config.vmax);
json.at("tmax").get_to(config.tmax);
json.at("cof").get_to(config.cof);
json.at("bumper").get_to(config.bumpers);
json.at("differentialTrackWidth").get_to(config.differentialTrackWidth);
}
Expand Down
Loading

0 comments on commit 34e4a48

Please # to comment.