Skip to content

Commit

Permalink
Updated TrajOpt planner unit test
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 authored and Levi-Armstrong committed Oct 2, 2019
1 parent 9e7666d commit 89888fb
Showing 1 changed file with 12 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -239,8 +239,8 @@ TEST_F(TesseractPlanningTrajoptUnit, TrajoptFreespacePlanner2)
std::make_shared<JointWaypoint>(std::vector<double>({ 0, 0, 0, -1.57, 0, 0, 0 }), joint_names);

// Specify a Cartesian Waypoint as the finish
config.end_waypoint_ =
std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0));
config.end_waypoint_ = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0), "base_link");

// Create test planner used for testing problem creation
tesseract_tests::TrajOptFreespacePlannerTest test_planner;
Expand Down Expand Up @@ -284,8 +284,8 @@ TEST_F(TesseractPlanningTrajoptUnit, TrajoptFreespacePlanner3)
tesseract_ptr_->getFwdKinematicsManagerConst()->getFwdKinematicSolver("manipulator")->getJointNames();

// Specify a Cartesian Waypoint as the start
config.start_waypoint_ =
std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0));
config.start_waypoint_ = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0), "base_link");

// Specify a Joint Waypoint as the finish
config.end_waypoint_ = std::make_shared<JointWaypoint>(std::vector<double>({ 0, 0, 0, -1.57, 0, 0, 0 }), joint_names);
Expand Down Expand Up @@ -329,12 +329,12 @@ TEST_F(TesseractPlanningTrajoptUnit, TrajoptFreespacePlanner4)
config.num_steps_ = NUM_STEPS;

// Specify a Cartesian Waypoint as the start
config.start_waypoint_ =
std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0));
config.start_waypoint_ = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0), "base_link");

// Specify a Cartesian Waypoint as the finish
config.end_waypoint_ =
std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0));
config.end_waypoint_ = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-.20, .4, 0.2), Eigen::Quaterniond(0, 0, 1.0, 0), "base_link");

// Create test planner used for testing problem creation
tesseract_tests::TrajOptFreespacePlannerTest test_planner;
Expand Down Expand Up @@ -377,8 +377,8 @@ TEST_F(TesseractPlanningTrajoptUnit, TrajoptArrayPlanner0)
// These specify the series of points to be optimized
for (int ind = 0; ind < NUM_STEPS; ind++)
{
CartesianWaypoint::Ptr waypoint = std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-0.2 + ind * .02, 0.4, 0.8),
Eigen::Quaterniond(0, 1.0, 0, 0));
CartesianWaypoint::Ptr waypoint = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-0.2 + ind * .02, 0.4, 0.8), Eigen::Quaterniond(0, 1.0, 0, 0), "base_link");
waypoint->setIsCritical(true);
config.target_waypoints_.push_back(waypoint);
}
Expand Down Expand Up @@ -428,8 +428,8 @@ TEST_F(TesseractPlanningTrajoptUnit, TrajoptArrayPlanner1)
// These specify the series of points to be optimized
for (int ind = 0; ind < NUM_STEPS; ind++)
{
CartesianWaypoint::Ptr waypoint = std::make_shared<CartesianWaypoint>(Eigen::Vector3d(-0.2 + ind * .02, 0.4, 0.8),
Eigen::Quaterniond(0, 1.0, 0, 0));
CartesianWaypoint::Ptr waypoint = std::make_shared<CartesianWaypoint>(
Eigen::Vector3d(-0.2 + ind * .02, 0.4, 0.8), Eigen::Quaterniond(0, 1.0, 0, 0), "base_link");
waypoint->setIsCritical(false);
config.target_waypoints_.push_back(waypoint);
}
Expand Down

0 comments on commit 89888fb

Please sign in to comment.