Skip to content

Commit

Permalink
Fix compilation
Browse files Browse the repository at this point in the history
  • Loading branch information
pjreiniger committed Oct 7, 2024
1 parent a55a834 commit c30e240
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 22 deletions.
7 changes: 4 additions & 3 deletions tests/cpp/pathplannerlib-cpp/main.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@

#include <pathplanner/lib/path/PathPlannerPath.h>
#include <pathplanner/lib/path/PathPlannerTrajectory.h>
#include <pathplanner/lib/trajectory/PathPlannerTrajectory.h>

#include <iostream>

Expand All @@ -11,11 +11,12 @@ int main() {
frc::Pose2d(1.0_m, 1.0_m, frc::Rotation2d(0_deg)),
frc::Pose2d(3.0_m, 1.0_m, frc::Rotation2d(0_deg)),
frc::Pose2d(5.0_m, 3.0_m, frc::Rotation2d(90_deg))};
std::vector<frc::Translation2d> bezierPoints =
PathPlannerPath::bezierFromPoses(poses);
std::vector<pathplanner::Waypoint> bezierPoints =
PathPlannerPath::waypointsFromPoses(poses);

auto path = std::make_shared<PathPlannerPath>(
bezierPoints,
PathConstraints(3.0_mps, 3.0_mps_sq, 360_deg_per_s, 720_deg_per_s_sq),
std::nullopt,
GoalEndState(0.0_mps, frc::Rotation2d(-90_deg)));
}
7 changes: 4 additions & 3 deletions tests/cpp/pathplannerlib-cpp/test.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@

#include <pathplanner/lib/path/PathPlannerPath.h>
#include <pathplanner/lib/path/PathPlannerTrajectory.h>
#include <pathplanner/lib/trajectory/PathPlannerTrajectory.h>

#include "gtest/gtest.h"

Expand All @@ -11,11 +11,12 @@ TEST(BasicTest, Basic) {
frc::Pose2d(1.0_m, 1.0_m, frc::Rotation2d(0_deg)),
frc::Pose2d(3.0_m, 1.0_m, frc::Rotation2d(0_deg)),
frc::Pose2d(5.0_m, 3.0_m, frc::Rotation2d(90_deg))};
std::vector<frc::Translation2d> bezierPoints =
PathPlannerPath::bezierFromPoses(poses);
std::vector<pathplanner::Waypoint> bezierPoints =
PathPlannerPath::waypointsFromPoses(poses);

auto path = std::make_shared<PathPlannerPath>(
bezierPoints,
PathConstraints(3.0_mps, 3.0_mps_sq, 360_deg_per_s, 720_deg_per_s_sq),
std::nullopt,
GoalEndState(0.0_mps, frc::Rotation2d(-90_deg)));
}
13 changes: 5 additions & 8 deletions tests/java/pathplannerlibjava/BasicTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,17 @@
import com.pathplanner.lib.path.GoalEndState;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.path.PathPlannerTrajectory;
import com.pathplanner.lib.path.Waypoint;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import java.util.List;
import org.junit.jupiter.api.Test;

class BasicTest {
@Test
void basicTest() {
List<Translation2d> bezierPoints =
PathPlannerPath.bezierFromPoses(
List<Waypoint> bezierPoints =
PathPlannerPath.waypointsFromPoses(
new Pose2d(1.0, 1.0, Rotation2d.fromDegrees(0)),
new Pose2d(3.0, 1.0, Rotation2d.fromDegrees(0)),
new Pose2d(5.0, 3.0, Rotation2d.fromDegrees(90)));
Expand All @@ -26,10 +24,9 @@ void basicTest() {
new PathPlannerPath(
bezierPoints,
new PathConstraints(3.0, 3.0, 2 * Math.PI, 4 * Math.PI),
null,
new GoalEndState(0.0, Rotation2d.fromDegrees(-90)));

PathPlannerTrajectory traj1 =
new PathPlannerTrajectory(path, new ChassisSpeeds(), Rotation2d.fromDegrees(0));
assertTrue(traj1.getStates().size() > 0);
assertTrue(path.getWaypoints().size() > 0);
}
}
13 changes: 5 additions & 8 deletions tests/java/pathplannerlibjava/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,17 @@
import com.pathplanner.lib.path.GoalEndState;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.path.PathPlannerTrajectory;
import com.pathplanner.lib.path.Waypoint;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import java.util.List;

public final class Main {
private Main() {}

public static void main(String[] args) {
List<Translation2d> bezierPoints =
PathPlannerPath.bezierFromPoses(
List<Waypoint> bezierPoints =
PathPlannerPath.waypointsFromPoses(
new Pose2d(1.0, 1.0, Rotation2d.fromDegrees(0)),
new Pose2d(3.0, 1.0, Rotation2d.fromDegrees(0)),
new Pose2d(5.0, 3.0, Rotation2d.fromDegrees(90)));
Expand All @@ -24,10 +22,9 @@ public static void main(String[] args) {
new PathPlannerPath(
bezierPoints,
new PathConstraints(3.0, 3.0, 2 * Math.PI, 4 * Math.PI),
null,
new GoalEndState(0.0, Rotation2d.fromDegrees(-90)));

PathPlannerTrajectory traj1 =
new PathPlannerTrajectory(path, new ChassisSpeeds(), Rotation2d.fromDegrees(0));
System.out.println(traj1);
System.out.println(path);
}
}

0 comments on commit c30e240

Please sign in to comment.