19#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <autoware_msgs/msg/lane.hpp>
25#include <trajectory_utils/trajectory_utils.hpp>
27#include <pure_pursuit/pure_pursuit.hpp>
28#include <gtest/gtest_prod.h>
33using WaypointPub = std::function<void(autoware_msgs::msg::Lane)>;
35namespace pure_pursuit = autoware::motion::control::pure_pursuit;
50 rcl_interfaces::msg::SetParametersResult
69 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>
remove_repeated_timestamps(
const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& traj_points);
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);
80 std::shared_ptr<pure_pursuit::PurePursuit>
pp_;
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
PurePursuitWrapperConfig config_
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 > ¶meters)
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.