diff --git a/packages/pure_pursuit/CMakeLists.txt b/packages/pure_pursuit/CMakeLists.txt new file mode 100644 index 0000000..888dc66 --- /dev/null +++ b/packages/pure_pursuit/CMakeLists.txt @@ -0,0 +1,44 @@ +cmake_minimum_required(VERSION 3.8) +project(pure_pursuit) + +add_compile_options(-Wall -Wextra -Wpedantic) + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(wbb_msgs REQUIRED) +find_package(visualization_msgs REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +add_executable(pursuit src/main.cpp src/pursuit.cpp) + +target_include_directories(pursuit PUBLIC + $ + $) + +target_compile_features(pursuit PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +ament_target_dependencies( + pursuit + rclcpp + visualization_msgs + wbb_msgs ) + + +install(TARGETS pursuit + DESTINATION lib/${PROJECT_NAME}) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/packages/pure_pursuit/include/pure_pursuit/pursuit.h b/packages/pure_pursuit/include/pure_pursuit/pursuit.h new file mode 100644 index 0000000..2a7e571 --- /dev/null +++ b/packages/pure_pursuit/include/pure_pursuit/pursuit.h @@ -0,0 +1,86 @@ +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace wbb +{ + +using namespace std::placeholders; + +class PurePursuit : public rclcpp::Node +{ + public: + PurePursuit(); + private: + void handleTrajectory(wbb_msgs::msg::ImagePath::SharedPtr trajectory); + + void handleBotPose(wbb_msgs::msg::ImagePose::SharedPtr bot_pose); + + void handlePixelScale(wbb_msgs::msg::ImagePixelScale::SharedPtr scale); + + double calculateDistance(wbb_msgs::msg::ImagePoint::SharedPtr first, + wbb_msgs::msg::ImagePose::SharedPtr second); + + std::pair calculateCurvature(wbb_msgs::msg::ImagePoint::SharedPtr lookahead, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale); + +// wbb_msgs::msg::ImagePoint findClosest(wbb_msgs::msg::ImagePath::SharedPtr trajectory, +// wbb_msgs::msg::ImagePose::SharedPtr bot_pose); + + wbb_msgs::msg::ImagePoint::SharedPtr checkSegment(wbb_msgs::msg::ImagePoint start, + wbb_msgs::msg::ImagePoint end, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, + double scale); + + wbb_msgs::msg::ImagePoint::SharedPtr findLookahead(wbb_msgs::msg::ImagePath::SharedPtr trajectory, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, + double scale); + + void visualizeLookahead(wbb_msgs::msg::ImagePoint::SharedPtr lookahead, double scale); + + void visualizeRadius(double curvature, wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale); + + void visualizeLARadius(wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale); + + void sendControlCommand(); + + struct Slols + { + rclcpp::Subscription::SharedPtr trajectory = nullptr; + rclcpp::Subscription::SharedPtr bot_pose = nullptr; + rclcpp::Subscription::SharedPtr scale = nullptr; + } slot_; + struct Signals + { + rclcpp::Publisher::SharedPtr control = nullptr; + rclcpp::Publisher::SharedPtr visual = nullptr; + } signal_; + + struct State + { + wbb_msgs::msg::ImagePath::SharedPtr trajectory = nullptr; + wbb_msgs::msg::ImagePose::SharedPtr bot_pose = nullptr; + wbb_msgs::msg::ImagePixelScale::SharedPtr scale = nullptr; + wbb_msgs::msg::ImagePoint::SharedPtr last_point = nullptr; + } state_; + + std::chrono::duration timeout_{0.20}; + double lookahead_distance; + size_t trajectory_pos; + rclcpp::TimerBase::SharedPtr timer_ = nullptr; +}; + +} // namespace wbb + + + + diff --git a/packages/pure_pursuit/package.xml b/packages/pure_pursuit/package.xml new file mode 100644 index 0000000..8a22caa --- /dev/null +++ b/packages/pure_pursuit/package.xml @@ -0,0 +1,20 @@ + + + + pure_pursuit + 0.0.0 + Simple whiteboard bot trajectory pursuit + enaix + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + rclcpp + wbb_msgs + + + ament_cmake + + diff --git a/packages/pure_pursuit/src/main.cpp b/packages/pure_pursuit/src/main.cpp new file mode 100644 index 0000000..68351c5 --- /dev/null +++ b/packages/pure_pursuit/src/main.cpp @@ -0,0 +1,11 @@ +#include + +#include "pure_pursuit/pursuit.h" + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/packages/pure_pursuit/src/pursuit.cpp b/packages/pure_pursuit/src/pursuit.cpp new file mode 100644 index 0000000..022fdbd --- /dev/null +++ b/packages/pure_pursuit/src/pursuit.cpp @@ -0,0 +1,304 @@ +#include "pure_pursuit/pursuit.h" + +namespace wbb +{ + +PurePursuit::PurePursuit() : Node("pure_pursuit") +{ + const auto qos = static_cast( + this->declare_parameter("qos", RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT)); + + std::chrono::duration period = std::chrono::duration( + this->declare_parameter("period", 0.02)); + lookahead_distance = this->declare_parameter("lookahead", 0.2); + trajectory_pos = 0; + + timer_ = this->create_wall_timer(period, std::bind(&PurePursuit::sendControlCommand, this)); + + slot_.trajectory = this->create_subscription( + "/robot/motion", 1, std::bind(&PurePursuit::handleTrajectory, this, _1) + ); + + slot_.bot_pose = this->create_subscription( + "/robot/ego", rclcpp::QoS(1).reliability(qos), + std::bind(&PurePursuit::handleBotPose, this, _1) + ); + + slot_.scale = this->create_subscription( + "/board/scale", 1, std::bind(&PurePursuit::handlePixelScale, this, _1) + ); + + signal_.control = this->create_publisher("/movement", 1); + signal_.visual = this->create_publisher("/robot/control/marker", 10); +} + +void PurePursuit::handleTrajectory(wbb_msgs::msg::ImagePath::SharedPtr trajectory) +{ + if (trajectory != state_.trajectory) + { + state_.trajectory = std::move(trajectory); + trajectory_pos = 0; + } +} + +void PurePursuit::handleBotPose(wbb_msgs::msg::ImagePose::SharedPtr bot_pose) +{ + state_.bot_pose = std::move(bot_pose); +} + +void PurePursuit::handlePixelScale(wbb_msgs::msg::ImagePixelScale::SharedPtr scale) +{ + state_.scale = std::move(scale); +} + +double PurePursuit::calculateDistance(wbb_msgs::msg::ImagePoint::SharedPtr first, + wbb_msgs::msg::ImagePose::SharedPtr second) +{ + return std::sqrt(std::pow(first->x - second->x, 2) + + std::pow(first->y - second->y, 2)); +} + +std::pair PurePursuit::calculateCurvature(wbb_msgs::msg::ImagePoint::SharedPtr lookahead, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale) +{ + double chord = calculateDistance(lookahead, bot_pose); + + if (chord == 0 || scale == 0) + return {0.0, 0.0}; + + double alpha = std::atan2(lookahead->y - bot_pose->y, lookahead->x - bot_pose->x) - + M_PI / 2 + bot_pose->theta; + + chord *= scale; + double velocity = 0.5; + if (std::sin(alpha) < 0) + velocity *= -1; + + if (std::cos(alpha) >= 0) + return {(2 * std::abs(std::sin(alpha))) / chord, velocity}; + return {-(2 * std::abs(std::sin(alpha))) / chord, velocity}; +} + +/*wbb_msgs::msg::ImagePoint findClosest(wbb_msgs::msg::ImagePath::SharedPtr trajectory, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose) +{ + double min_dist = calculateDistance(trajectory->points[0], bot_pose); + wbb_msgs::msg::ImagePoint min_point = trajectory->points[0]; + + for (auto point : trajectory->points) + { + double distance = calculateDistance(point, bot_pose); + if (distance < min_dist) + { + min_dist = distance; + min_point = point; + } + } + + return min_point; +}*/ + +wbb_msgs::msg::ImagePoint::SharedPtr PurePursuit::checkSegment(wbb_msgs::msg::ImagePoint start, + wbb_msgs::msg::ImagePoint end, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, + double scale) +{ + double vector_dot_a = std::pow(end.x - start.x, 2) + std::pow(end.y - start.y, 2); + + double vector_dot_b = 2 * (start.x - bot_pose->x) * (end.x - start.x) + + 2 * (start.y - bot_pose->y) * (end.y - start.y); + + double vector_dot_c = std::pow(start.x - bot_pose->x, 2) + + std::pow(start.y - bot_pose->y, 2) - std::pow(lookahead_distance / scale, 2); + + double discr = std::pow(vector_dot_b, 2) - 4 * vector_dot_a * vector_dot_c; + + if (discr < 0 || vector_dot_a == 0) + return nullptr; + + discr = std::sqrt(discr); + + double t1 = (-vector_dot_b - discr) / (2 * vector_dot_a); + double t2 = (-vector_dot_b + discr) / (2 * vector_dot_a); + + if (t1 >= 0 && t1 <= 1) + { + wbb_msgs::msg::ImagePoint pt; + pt.x = start.x + t1 * (end.x - start.x); + pt.y = start.y + t1 * (end.y - start.y); + return std::make_shared(pt); + } + if (t2 >= 0 && t2 <= 1) + { + wbb_msgs::msg::ImagePoint pt; + pt.x = start.x + t2 * (end.x - start.x); + pt.y = start.y + t2 * (end.y - start.y); + return std::make_shared(pt); + } + + return nullptr; +} + +wbb_msgs::msg::ImagePoint::SharedPtr PurePursuit::findLookahead(wbb_msgs::msg::ImagePath::SharedPtr trajectory, + wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale) +{ + for (size_t i = trajectory_pos + 1; i < trajectory->points.size(); i++) + { + wbb_msgs::msg::ImagePoint::SharedPtr pt = checkSegment(trajectory->points[i - 1],trajectory->points[i], + bot_pose, scale); + if (!pt) + continue; + + if (state_.last_point && state_.last_point != pt) + trajectory_pos++; + + state_.last_point = pt; + return pt; + } + + return nullptr; +} + +void PurePursuit::visualizeLookahead(wbb_msgs::msg::ImagePoint::SharedPtr lookahead, double scale) +{ + visualization_msgs::msg::ImageMarker vis_msg; + vis_msg.type = visualization_msgs::msg::ImageMarker::CIRCLE; + vis_msg.ns = "0"; + vis_msg.action = visualization_msgs::msg::ImageMarker::ADD; + + std_msgs::msg::ColorRGBA color; + + color.r = 0.0; + color.g = 0.0; + color.b = 1.0; + color.a = 1.0; + + vis_msg.outline_color = color; + vis_msg.fill_color = color; + vis_msg.filled = 1; + vis_msg.scale = 0.1 * scale; + + geometry_msgs::msg::Point pt; + pt.x = lookahead->x * scale; + pt.y = lookahead->y * scale; + + vis_msg.position = pt; + //vis_msg.lifetime = timeout_; + + signal_.visual->publish(vis_msg); +} + +void PurePursuit::visualizeLARadius(wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale) +{ + visualization_msgs::msg::ImageMarker vis_msg; + vis_msg.type = visualization_msgs::msg::ImageMarker::CIRCLE; + vis_msg.ns = "1"; + vis_msg.action = visualization_msgs::msg::ImageMarker::ADD; + + std_msgs::msg::ColorRGBA color; + + color.r = 0.0; + color.g = 0.5; + color.b = 0.5; + color.a = 1.0; + + vis_msg.outline_color = color; + vis_msg.filled = 0; + vis_msg.scale = int(lookahead_distance / scale); + + geometry_msgs::msg::Point pt; + pt.x = bot_pose->x; + pt.y = bot_pose->y; + vis_msg.position = pt; + + signal_.visual->publish(vis_msg); +} + +void PurePursuit::visualizeRadius(double curvature, wbb_msgs::msg::ImagePose::SharedPtr bot_pose, double scale) +{ + visualization_msgs::msg::ImageMarker vis_msg; + vis_msg.type = visualization_msgs::msg::ImageMarker::CIRCLE; + vis_msg.ns = "2"; + vis_msg.action = visualization_msgs::msg::ImageMarker::ADD; + + double radius = 100 / scale; + if (curvature != 0 && scale != 0) + radius = 1 / (curvature * scale); + + geometry_msgs::msg::Point pt; + if (radius >= 0) + { + double angle = bot_pose->theta + M_PI / 2; + pt.x = int(radius * std::cos(angle)) + bot_pose->x; + pt.y = int(radius * std::sin(angle)) + bot_pose->y; + } + else + { + double angle = bot_pose->theta - M_PI / 2; + pt.x = bot_pose->x - int(-radius * std::cos(angle)); + pt.y = bot_pose->y - int(-radius * std::sin(angle)); + } + + vis_msg.position = pt; + + std_msgs::msg::ColorRGBA color; + + color.r = 0.0; + color.g = 1.0; + color.b = 0.0; + color.a = 1.0; + + vis_msg.outline_color = color; + vis_msg.filled = 0; + vis_msg.scale = int(radius); + + //vis_msg.lifetime = timeout_; + + signal_.visual->publish(vis_msg); +} + +void PurePursuit::sendControlCommand() +{ + auto stop = [this]() + { + wbb_msgs::msg::Control msg; + msg.curvature = 0; + msg.velocity = 0; + signal_.control->publish(msg); + }; + + if (!(state_.trajectory && state_.bot_pose && state_.scale)) + { + stop(); + return; + } + + wbb_msgs::msg::ImagePose bot_pose_src = *state_.bot_pose; + wbb_msgs::msg::ImagePose::SharedPtr bot_pose = std::make_shared(bot_pose_src); + + double scale = std::pow(std::cos(bot_pose->theta), 2) * state_.scale->scale_x + + std::pow(std::sin(bot_pose->theta), 2) * state_.scale->scale_y; + + //visualizeLARadius(bot_pose, scale); + + wbb_msgs::msg::ImagePoint::SharedPtr lh = findLookahead(state_.trajectory, bot_pose, scale); + + if (!lh) + { + stop(); + return; + } + + visualizeLookahead(lh, scale); + + wbb_msgs::msg::Control msg; + std::pair prop = calculateCurvature(lh, bot_pose, scale); + msg.curvature = prop.first; + visualizeRadius(msg.curvature, bot_pose, scale); + msg.velocity = prop.second; + if (msg.curvature != 0) + RCLCPP_INFO(this->get_logger(), "%f %f", 1/msg.curvature, msg.velocity); + signal_.control->publish(msg); +} + +} // namespace wbb \ No newline at end of file