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

AUTO-2570 Use odom based pose stream for CAPTURE #39

Merged
merged 1 commit into from
Jun 11, 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
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "pluginlib/class_loader.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "geometry_msgs/msg/pose2_d.hpp"
#include "std_msgs/msg/bool.hpp"
#include "nav2_regulated_pure_pursuit_controller/path_handler.hpp"
#include "nav2_regulated_pure_pursuit_controller/collision_checker.hpp"
#include "nav2_regulated_pure_pursuit_controller/parameter_handler.hpp"
Expand Down Expand Up @@ -218,12 +219,15 @@ class RegulatedPurePursuitController : public nav2_core::Controller
double control_duration_;
bool cancelling_ = false;
bool finished_cancelling_ = false;
bool is_rotating_to_heading_ = false;

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
carrot_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
curvature_carrot_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Bool>>
is_rotating_to_heading_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_;
std::unique_ptr<nav2_regulated_pure_pursuit_controller::PathHandler> path_handler_;
std::unique_ptr<nav2_regulated_pure_pursuit_controller::ParameterHandler> param_handler_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ void RegulatedPurePursuitController::configure(
carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>("lookahead_point", 1);
curvature_carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
"curvature_lookahead_point", 1);
is_rotating_to_heading_pub_ = node->create_publisher<std_msgs::msg::Bool>(
"is_rotating_to_heading", 1);
}

void RegulatedPurePursuitController::cleanup()
Expand All @@ -88,6 +90,7 @@ void RegulatedPurePursuitController::cleanup()
global_path_pub_.reset();
carrot_pub_.reset();
curvature_carrot_pub_.reset();
is_rotating_to_heading_pub_.reset();
}

void RegulatedPurePursuitController::activate()
Expand All @@ -100,6 +103,7 @@ void RegulatedPurePursuitController::activate()
global_path_pub_->on_activate();
carrot_pub_->on_activate();
curvature_carrot_pub_->on_activate();
is_rotating_to_heading_pub_->on_activate();
}

void RegulatedPurePursuitController::deactivate()
Expand All @@ -112,6 +116,7 @@ void RegulatedPurePursuitController::deactivate()
global_path_pub_->on_deactivate();
carrot_pub_->on_deactivate();
curvature_carrot_pub_->on_deactivate();
is_rotating_to_heading_pub_->on_deactivate();
}

std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
Expand Down Expand Up @@ -228,11 +233,14 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
// - otherwise equal to curvature_lookahead_pose (which can be interpolated after goal)
double angle_to_heading;
if (shouldRotateToGoalHeading(carrot_pose)) {
is_rotating_to_heading_ = true;
double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
} else if (shouldRotateToPath(rotate_to_path_carrot_pose, angle_to_heading, x_vel_sign)) {
is_rotating_to_heading_ = true;
rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
} else {
is_rotating_to_heading_ = false;
applyConstraints(
regulation_curvature, speed,
collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
Expand Down Expand Up @@ -267,6 +275,11 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
throw nav2_core::NoValidControl("RegulatedPurePursuitController detected collision ahead!");
}

// Publish whether we are rotating to goal heading
std_msgs::msg::Bool is_rotating_to_heading_msg;
is_rotating_to_heading_msg.data = is_rotating_to_heading_;
is_rotating_to_heading_pub_->publish(is_rotating_to_heading_msg);

// populate and return message
geometry_msgs::msg::TwistStamped cmd_vel;
cmd_vel.header = pose.header;
Expand Down
Loading