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

Specify goal loiter direction #68

Merged
merged 1 commit into from
Aug 14, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
15 changes: 15 additions & 0 deletions terrain_planner/include/terrain_planner/terrain_ompl_rrt.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,21 @@ class TerrainOmplRrt {
*/
void setupProblem(const Eigen::Vector3d& start_pos, const Eigen::Vector3d& goal, double start_loiter_radius);

/**
* @brief Setup problem with center position of start and goal loiter circle with specific radius
*
* @param start_pos
* @param goal
* @param start_loiter_radius
* - Positive: anti clockwise
* - Negative: Clockwise
* @param goal_loiter_radius
* - Positive: anti clockwise
* - Negative: Clockwise
*/
void setupProblem(const Eigen::Vector3d& start_pos, const Eigen::Vector3d& goal, double start_loiter_radius,
double goal_loiter_radius);

/**
* @brief Setup problem with position, velocity of the start and center of the goal loiter circle
*
Expand Down
39 changes: 39 additions & 0 deletions terrain_planner/src/terrain_ompl_rrt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,45 @@ void TerrainOmplRrt::setupProblem(const Eigen::Vector3d& start_pos, const Eigen:
// std::cout << "Planner Range: " << planner_ptr->as<ompl::geometric::RRTstar>()->getRange() << std::endl;
}

void TerrainOmplRrt::setupProblem(const Eigen::Vector3d& start_pos, const Eigen::Vector3d& goal,
double start_loiter_radius, double goal_loiter_radius) {
configureProblem();
double radius =
problem_setup_->getStateSpace()->as<fw_planning::spaces::DubinsAirplaneStateSpace>()->getMinTurningRadius();
double delta_theta = 0.1;
for (double theta = -M_PI; theta < M_PI; theta += (delta_theta * 2 * M_PI)) {
ompl::base::ScopedState<fw_planning::spaces::DubinsAirplaneStateSpace> start_ompl(
problem_setup_->getSpaceInformation());

start_ompl->setX(start_pos(0) + std::abs(start_loiter_radius) * std::cos(theta));
start_ompl->setY(start_pos(1) + std::abs(start_loiter_radius) * std::sin(theta));
start_ompl->setZ(start_pos(2));
double start_yaw = bool(start_loiter_radius > 0) ? theta - M_PI_2 : theta + M_PI_2;
wrap_pi(start_yaw);
start_ompl->setYaw(start_yaw);
problem_setup_->addStartState(start_ompl);
}

goal_states_ = std::make_shared<ompl::base::GoalStates>(problem_setup_->getSpaceInformation());
for (double theta = -M_PI; theta < M_PI; theta += (delta_theta * 2 * M_PI)) {
ompl::base::ScopedState<fw_planning::spaces::DubinsAirplaneStateSpace> goal_ompl(
problem_setup_->getSpaceInformation());
goal_ompl->setX(goal(0) + std::abs(goal_loiter_radius) * std::cos(theta));
goal_ompl->setY(goal(1) + std::abs(goal_loiter_radius) * std::sin(theta));
goal_ompl->setZ(goal(2));
double goal_yaw = bool(goal_loiter_radius > 0) ? theta - M_PI_2 : theta + M_PI_2;
wrap_pi(goal_yaw);
goal_ompl->setYaw(goal_yaw);
goal_states_->addState(goal_ompl);
}
problem_setup_->setGoal(goal_states_);

problem_setup_->setup();

auto planner_ptr = problem_setup_->getPlanner();
// std::cout << "Planner Range: " << planner_ptr->as<ompl::geometric::RRTstar>()->getRange() << std::endl;
}

void TerrainOmplRrt::setupProblem(const Eigen::Vector3d& start_pos, const Eigen::Vector3d& start_vel,
const Eigen::Vector3d& goal, double goal_radius) {
configureProblem();
Expand Down
Loading