Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
pure_pursuit_wrapper.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018-2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <functional>
18// ROS
19#include <rclcpp/rclcpp.hpp>
20// msgs
21#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <autoware_msgs/msg/lane.hpp>
24#include <algorithm>
25#include <trajectory_utils/trajectory_utils.hpp>
27#include <pure_pursuit/pure_pursuit.hpp>
28#include <gtest/gtest_prod.h>
30
32
33using WaypointPub = std::function<void(autoware_msgs::msg::Lane)>;
34using PluginDiscoveryPub = std::function<void(carma_planning_msgs::msg::Plugin)>;
35namespace pure_pursuit = autoware::motion::control::pure_pursuit;
36
38{
39 public:
43 explicit PurePursuitWrapperNode(const rclcpp::NodeOptions& options);
44
45 autoware_msgs::msg::ControlCommandStamped generate_command() override;
46
50 rcl_interfaces::msg::SetParametersResult
51 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
52
56 carma_ros2_utils::CallbackReturn on_configure_plugin() override;
57
58 bool get_availability() override;
59
60 std::string get_version_id() override;
61
69 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> remove_repeated_timestamps(const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& traj_points);
70
71 //CONVERSIONS
72
73 motion::motion_common::State convert_state(geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist);
74 autoware_msgs::msg::ControlCommandStamped convert_cmd(motion::motion_common::Command cmd);
75
76 private:
77
79
80 std::shared_ptr<pure_pursuit::PurePursuit> pp_;
81
82 std::shared_ptr<pure_pursuit::PurePursuit> get_pure_pursuit_worker()
83 {
84 return pp_;
85 }
86
87 // Unit Test Accessors
88 FRIEND_TEST(PurePursuitTest, sanity_check);
89
90};
91
92} // namespace pure_pursuit_wrapper
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
std::shared_ptr< pure_pursuit::PurePursuit > pp_
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
std::shared_ptr< pure_pursuit::PurePursuit > get_pure_pursuit_worker()
FRIEND_TEST(PurePursuitTest, sanity_check)
autoware_msgs::msg::ControlCommandStamped convert_cmd(motion::motion_common::Command cmd)
motion::motion_common::State convert_state(geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist)
std::string get_version_id() override
Returns the version id of this plugin.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > remove_repeated_timestamps(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &traj_points)
Drops any points that sequentially have same target_time and return new trajectory_points in order to...
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.
PurePursuitWrapperNode(const rclcpp::NodeOptions &options)
Constructor.
std::function< void(carma_planning_msgs::msg::Plugin)> PluginDiscoveryPub
std::function< void(autoware_msgs::msg::Lane)> WaypointPub
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig.