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.
inlanecruising_plugin.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <vector>
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>
26#include <carma_wm/Geometry.hpp>
28#include <carma_planning_msgs/srv/plan_trajectory.hpp>
30#include <functional>
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>
37
39{
40using PublishPluginDiscoveryCB = std::function<void(const carma_planning_msgs::msg::Plugin&)>;
41using DebugPublisher = std::function<void(const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds&)>;
43
44static const std::string ILC_LOGGER = "inlanecruising_plugin";
45
51{
52public:
62 InLaneCruisingPlugin(std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh,
64 const InLaneCruisingPluginConfig& config,
65 const DebugPublisher& debug_publisher=[](const auto& msg){},
66 const std::string& plugin_name = "inlanecruising_plugin",
67 const std::string& version_id = "v1.0");
68
77 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
78 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp);
79
85 void set_yield_client(carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> client);
86
87 carma_planning_msgs::msg::VehicleState ending_state_before_buffer_; //state before applying extra points for curvature calculation that are removed later
88
89private:
90
91 std::string plugin_name_;
92 std::string version_id_;
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_;
99
100 // Access members for unit test
101 FRIEND_TEST(InLaneCruisingPluginTest, rostest1);
102};
103
104
105
106}; // namespace inlanecruising_plugin
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.
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.
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
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
string version_id
Stuct containing the algorithm configuration values for the InLaneCruisingPlugin.