20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
21#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
22#include <carma_planning_msgs/msg/plugin.hpp>
23#include <boost/shared_ptr.hpp>
24#include <carma_ros2_utils/carma_lifecycle_node.hpp>
25#include <boost/geometry.hpp>
28#include <carma_planning_msgs/srv/plan_trajectory.hpp>
32#include <unordered_set>
33#include <autoware_msgs/msg/lane.h>
34#include <rclcpp/rclcpp.hpp>
35#include <carma_debug_ros2_msgs/msg/trajectory_curvature_speeds.hpp>
36#include <gtest/gtest.h>
41using DebugPublisher = std::function<void(
const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds&)>;
44static const std::string
ILC_LOGGER =
"inlanecruising_plugin";
66 const std::string& plugin_name =
"inlanecruising_plugin",
77 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
78 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp);
85 void set_yield_client(carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> client);
95 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>
yield_client_;
97 carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds
debug_msg_;
98 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode>
nh_;
Class containing primary business logic for the In-Lane Cruising Plugin.
void set_yield_client(carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client)
set the yield service
FRIEND_TEST(InLaneCruisingPluginTest, rostest1)
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
void plan_trajectory_callback(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
Service callback for trajectory planning.
InLaneCruisingPluginConfig config_
carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds debug_msg_
carma_planning_msgs::msg::VehicleState ending_state_before_buffer_
InLaneCruisingPlugin(std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh, carma_wm::WorldModelConstPtr wm, const InLaneCruisingPluginConfig &config, const DebugPublisher &debug_publisher=[](const auto &msg){}, const std::string &plugin_name="inlanecruising_plugin", const std::string &version_id="v1.0")
Constructor.
carma_wm::WorldModelConstPtr wm_
DebugPublisher debug_publisher_
std::shared_ptr< const WorldModel > WorldModelConstPtr
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair
std::function< void(const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds &)> DebugPublisher
static const std::string ILC_LOGGER
std::function< void(const carma_planning_msgs::msg::Plugin &)> PublishPluginDiscoveryCB
Stuct containing the algorithm configuration values for the InLaneCruisingPlugin.