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

chore: sync upstream #1

Merged
merged 19 commits into from
Jan 24, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
3e27b12
fix(behavior_path): add minus and comments (#246)
h-ohta Jan 12, 2022
244268b
fix: use transient_local qos for route (#149)
1222-takeshi Jan 13, 2022
045009c
fix: ring outlier filter bug (#253)
satoshi-ota Jan 14, 2022
2b1c1b3
fix(behavior velocity planner): occlusion spot slice (#237)
taikitanaka3 Jan 17, 2022
1225511
fix(behavior_path_planner): add transformation to polygon, obj frame …
h-ohta Jan 17, 2022
31decd3
fix(ndt_scan_matcher): fix compiler flags and Eigen aligned allocator…
harihitode Jan 17, 2022
cd5b5e3
fix(lanelet2_extension): add guard for inner product (#256)
kyoichi-sugahara Jan 18, 2022
9843b8e
fix(system_monitor): fix build error on aarch64 (#263)
KeisukeShima Jan 18, 2022
fe14a99
feat(diagnostics_aggregator): remove map_version diagnostic from conf…
0x126 Jan 19, 2022
c143557
fix(lanelet2_extension): fix getAngleDifference (#264)
taikitanaka3 Jan 20, 2022
dd3b946
test(behavior velocity): fix unstable gtest (#273)
taikitanaka3 Jan 20, 2022
96215b8
fix(vehicle_cmd_gate): fix topic name (#274)
1222-takeshi Jan 20, 2022
1ad7818
feat: port pure_pursuit (#271)
rej55 Jan 21, 2022
02d1c39
fix(behavior_velocity_planner): fix inversion of object orientation i…
tkimura4 Jan 21, 2022
baeca25
feat: add covariance param (#281)
YamatoAndo Jan 21, 2022
a91d3f1
fix: typo in localization util.launch.py (#277)
YamatoAndo Jan 21, 2022
6d27a37
feat: add pose_initializer params (#279)
YamatoAndo Jan 21, 2022
7ecbd72
fix: particle distribution of initial pose estimatation (#278)
YamatoAndo Jan 21, 2022
10bd1c0
feat(route_handler): better avoidance drivable areas extension in beh…
zulfaqar-azmi-t4 Jan 24, 2022
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
52 changes: 52 additions & 0 deletions control/pure_pursuit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
cmake_minimum_required(VERSION 3.5)
project(pure_pursuit)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
endif()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

find_package(Eigen3 REQUIRED)


include_directories(
${EIGEN3_INCLUDE_DIRS}
)

# pure_pursuit_core
ament_auto_add_library(pure_pursuit_core SHARED
src/pure_pursuit_core/planning_utils.cpp
src/pure_pursuit_core/pure_pursuit.cpp
src/pure_pursuit_core/interpolate.cpp
)

# pure_pursuit
ament_auto_add_library(pure_pursuit_node SHARED
src/pure_pursuit/pure_pursuit_node.cpp
src/pure_pursuit/pure_pursuit_viz.cpp
)

target_link_libraries(pure_pursuit_node
pure_pursuit_core
)

rclcpp_components_register_node(pure_pursuit_node
PLUGIN "pure_pursuit::PurePursuitNode"
EXECUTABLE pure_pursuit_node_exe
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package(INSTALL_TO_SHARE
launch
)
9 changes: 9 additions & 0 deletions control/pure_pursuit/config/pure_pursuit.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
# -- system --
control_period: 0.033

# -- algorithm --
lookahead_distance_ratio: 2.2
min_lookahead_distance: 2.5
reverse_min_lookahead_distance: 7.0
88 changes: 88 additions & 0 deletions control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
// Copyright 2020 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* Copyright 2015-2019 Autoware Foundation. All rights reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef PURE_PURSUIT__PURE_PURSUIT_HPP_
#define PURE_PURSUIT__PURE_PURSUIT_HPP_

#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/pose.hpp>

#include <memory>
#include <utility>
#include <vector>

#define EIGEN_MPL2_ONLY
#include <Eigen/Core>
#include <Eigen/Geometry>

namespace pure_pursuit
{
class PurePursuit
{
public:
PurePursuit() : lookahead_distance_(0.0), clst_thr_dist_(3.0), clst_thr_ang_(M_PI / 4) {}
~PurePursuit() = default;

rclcpp::Logger logger = rclcpp::get_logger("pure_pursuit");
// setter
void setCurrentPose(const geometry_msgs::msg::Pose & msg);
void setWaypoints(const std::vector<geometry_msgs::msg::Pose> & msg);
void setLookaheadDistance(double ld) { lookahead_distance_ = ld; }
void setClosestThreshold(double clst_thr_dist, double clst_thr_ang)
{
clst_thr_dist_ = clst_thr_dist;
clst_thr_ang_ = clst_thr_ang;
}

// getter
geometry_msgs::msg::Point getLocationOfNextWaypoint() const { return loc_next_wp_; }
geometry_msgs::msg::Point getLocationOfNextTarget() const { return loc_next_tgt_; }

bool isDataReady();
std::pair<bool, double> run(); // calculate curvature

private:
// variables for debug
geometry_msgs::msg::Point loc_next_wp_;
geometry_msgs::msg::Point loc_next_tgt_;

// variables got from outside
double lookahead_distance_, clst_thr_dist_, clst_thr_ang_;
std::shared_ptr<std::vector<geometry_msgs::msg::Pose>> curr_wps_ptr_;
std::shared_ptr<geometry_msgs::msg::Pose> curr_pose_ptr_;

// functions
int32_t findNextPointIdx(int32_t search_start_idx);
std::pair<bool, geometry_msgs::msg::Point> lerpNextTarget(int32_t next_wp_idx);
};

} // namespace pure_pursuit

#endif // PURE_PURSUIT__PURE_PURSUIT_HPP_
128 changes: 128 additions & 0 deletions control/pure_pursuit/include/pure_pursuit/pure_pursuit_node.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
// Copyright 2020 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* Copyright 2015-2019 Autoware Foundation. All rights reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef PURE_PURSUIT__PURE_PURSUIT_NODE_HPP_
#define PURE_PURSUIT__PURE_PURSUIT_NODE_HPP_

#include "pure_pursuit/pure_pursuit.hpp"
#include "pure_pursuit/pure_pursuit_viz.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/self_pose_listener.hpp>

#include <autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <boost/optional.hpp> // To be replaced by std::optional in C++17

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <vector>

namespace pure_pursuit
{
struct Param
{
// Global Parameters
double wheel_base;

// Node Parameters
double ctrl_period;

// Algorithm Parameters
double lookahead_distance_ratio;
double min_lookahead_distance;
double reverse_min_lookahead_distance; // min_lookahead_distance in reverse gear
};

struct DebugData
{
geometry_msgs::msg::Point next_target;
};

class PurePursuitNode : public rclcpp::Node
{
public:
explicit PurePursuitNode(const rclcpp::NodeOptions & node_options);

private:
// Subscriber
tier4_autoware_utils::SelfPoseListener self_pose_listener_{this};
rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr sub_trajectory_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_current_odometry_;

autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr trajectory_;
nav_msgs::msg::Odometry::ConstSharedPtr current_odometry_;

bool isDataReady();

void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg);
void onCurrentOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);

// TF
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;

// Publisher
rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannLateralCommand>::SharedPtr
pub_ctrl_cmd_;

void publishCommand(const double target_curvature);

// Debug Publisher
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_debug_marker_;

void publishDebugMarker() const;

// Timer
rclcpp::TimerBase::SharedPtr timer_;
void onTimer();

// Parameter
Param param_;

// Algorithm
std::unique_ptr<PurePursuit> pure_pursuit_;

boost::optional<double> calcTargetCurvature();
boost::optional<autoware_auto_planning_msgs::msg::TrajectoryPoint> calcTargetPoint() const;

// Debug
mutable DebugData debug_data_;
};

} // namespace pure_pursuit

#endif // PURE_PURSUIT__PURE_PURSUIT_NODE_HPP_
47 changes: 47 additions & 0 deletions control/pure_pursuit/include/pure_pursuit/pure_pursuit_viz.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright 2020 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* Copyright 2015-2019 Autoware Foundation. All rights reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef PURE_PURSUIT__PURE_PURSUIT_VIZ_HPP_
#define PURE_PURSUIT__PURE_PURSUIT_VIZ_HPP_

#include <geometry_msgs/msg/pose_stamped.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <vector>
namespace pure_pursuit
{
visualization_msgs::msg::Marker createNextTargetMarker(
const geometry_msgs::msg::Point & next_target);

visualization_msgs::msg::Marker createTrajectoryCircleMarker(
const geometry_msgs::msg::Point & target, const geometry_msgs::msg::Pose & current_pose);
} // namespace pure_pursuit

#endif // PURE_PURSUIT__PURE_PURSUIT_VIZ_HPP_
55 changes: 55 additions & 0 deletions control/pure_pursuit/include/pure_pursuit/util/interpolate.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// Copyright 2018-2019 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PURE_PURSUIT__UTIL__INTERPOLATE_HPP_
#define PURE_PURSUIT__UTIL__INTERPOLATE_HPP_

#include <cmath>
#include <iostream>
#include <vector>

namespace pure_pursuit
{
class LinearInterpolate
{
public:
LinearInterpolate() {}
~LinearInterpolate() {}
static bool interpolate(
const std::vector<double> & base_index, const std::vector<double> & base_value,
const std::vector<double> & return_index, std::vector<double> & return_value);
};

class SplineInterpolate
{
bool initialized_ = false;
std::vector<double> a_; //!< @brief temporal vector for calculation
std::vector<double> b_; //!< @brief temporal vector for calculation
std::vector<double> c_; //!< @brief temporal vector for calculation
std::vector<double> d_; //!< @brief temporal vector for calculation

public:
SplineInterpolate();
explicit SplineInterpolate(const std::vector<double> & x);
~SplineInterpolate();
void generateSpline(const std::vector<double> & x);
double getValue(const double & s);
bool interpolate(
const std::vector<double> & base_index, const std::vector<double> & base_value,
const std::vector<double> & return_index, std::vector<double> & return_value);
void getValueVector(const std::vector<double> & s_v, std::vector<double> & value_v);
};
} // namespace pure_pursuit

#endif // PURE_PURSUIT__UTIL__INTERPOLATE_HPP_
Loading