Skip to content

Add pure pursuit node #6

Open
wants to merge 20 commits into
base: master
Choose a base branch
from
Open
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
44 changes: 44 additions & 0 deletions packages/pure_pursuit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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(<dependency> REQUIRED)

add_executable(pursuit src/main.cpp src/pursuit.cpp)

target_include_directories(pursuit PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>)

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()
86 changes: 86 additions & 0 deletions packages/pure_pursuit/include/pure_pursuit/pursuit.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
#pragma once

#include <chrono>
#include <cmath>
#include <functional>

#include <wbb_msgs/msg/image_path.hpp>
#include <wbb_msgs/msg/image_pose.hpp>
#include <wbb_msgs/msg/control.hpp>
#include <wbb_msgs/msg/image_pixel_scale.hpp>
#include <rclcpp/rclcpp.hpp>
#include <visualization_msgs/msg/image_marker.hpp>

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<double, double> 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<wbb_msgs::msg::ImagePath>::SharedPtr trajectory = nullptr;
rclcpp::Subscription<wbb_msgs::msg::ImagePose>::SharedPtr bot_pose = nullptr;
rclcpp::Subscription<wbb_msgs::msg::ImagePixelScale>::SharedPtr scale = nullptr;
} slot_;
struct Signals
{
rclcpp::Publisher<wbb_msgs::msg::Control>::SharedPtr control = nullptr;
rclcpp::Publisher<visualization_msgs::msg::ImageMarker>::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<double> timeout_{0.20};
double lookahead_distance;
size_t trajectory_pos;
rclcpp::TimerBase::SharedPtr timer_ = nullptr;
};

} // namespace wbb




20 changes: 20 additions & 0 deletions packages/pure_pursuit/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>pure_pursuit</name>
<version>0.0.0</version>
<description>Simple whiteboard bot trajectory pursuit</description>
<maintainer email="[email protected]">enaix</maintainer>
<license>TODO: License declaration</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>rclcpp</depend>
<depend>wbb_msgs</depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
11 changes: 11 additions & 0 deletions packages/pure_pursuit/src/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#include <rclcpp/rclcpp.hpp>

#include "pure_pursuit/pursuit.h"

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<wbb::PurePursuit>());
rclcpp::shutdown();
return 0;
}
Loading