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.
stop_and_dwell_strategic_plugin.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2023 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 <rclcpp/rclcpp.hpp>
20#include <string>
21#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
22#include <carma_planning_msgs/msg/plugin.hpp>
23#include <carma_planning_msgs/msg/guidance_state.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27#include <carma_wm/Geometry.hpp>
28#include <lanelet2_core/Forward.h>
29#include <gtest/gtest_prod.h>
30#include <boost/property_tree/ptree.hpp>
31#include <boost/property_tree/json_parser.hpp>
32#include <boost/algorithm/string/split.hpp>
33#include <boost/algorithm/string/classification.hpp>
36
38{
39
44 {
45 rclcpp::Time stamp; // Timestamp of this state data
46 double downtrack; // The downtrack of the vehicle along the route at time stamp
47 double speed; // The speed of the vehicle at time stamp
48 lanelet::Id lane_id; // The current lane id of the vehicle at time stamp
49 };
50
52{
53public:
54
58 explicit StopAndDwellStrategicPlugin(const rclcpp::NodeOptions &);
59
67 std::shared_ptr<rmw_request_id_t> srv_header,
68 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
69 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp);
70
74 rcl_interfaces::msg::SetParametersResult
75 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
76
81 void currentPoseCb(geometry_msgs::msg::PoseStamped::UniquePtr msg);
82
97 carma_planning_msgs::msg::Maneuver composeLaneFollowingManeuverMessage(double start_dist, double end_dist, double start_speed,
98 double target_speed, rclcpp::Time start_time, double time_to_stop,
99 std::vector<lanelet::Id> lane_ids);
100
101 carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double current_dist, double end_dist, double start_speed,
102 const lanelet::Id& starting_lane_id, const lanelet::Id& ending_lane_id,
103 double stopping_accel, rclcpp::Time start_time, rclcpp::Time end_time) const;
104
105
114 VehicleState extractInitialState(const carma_planning_msgs::srv::PlanManeuvers::Request& req) const;
115
121 std::vector<lanelet::ConstLanelet> getLaneletsBetweenWithException(double start_downtrack, double end_downtrack,
122 bool shortest_path_only = false,
123 bool bounds_inclusive = true) const;
124
125
135 double findSpeedLimit(const lanelet::ConstLanelet& llt) const;
136
141 void guidance_state_cb(const carma_planning_msgs::msg::GuidanceState::UniquePtr msg);
142
151 VehicleState extractInitialState(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req) const;
152
154 carma_ros2_utils::CallbackReturn on_configure_plugin();
155 carma_ros2_utils::CallbackReturn on_activate_plugin();
156
157 bool get_availability();
158 std::string get_version_id();
159
160
162
163 bool vehicle_engaged_ = false;
164
165 // approximate speed limit
166 double speed_limit_ = 100.0;
167
168 // downtrack of host vehicle
169 double current_downtrack_ = 0.0;
170 // downtrack of bus stop
172 bool first_stop_ = true;
173 rclcpp::Time time_to_move_;
174 std::string logger_name_="stop_and_dwell_strategic_plugin";
175
176 double max_comfort_accel_ = 2.0; // acceleration rates after applying miltiplier
177 double max_comfort_decel_ = -2.0;
179
181
182 private:
183
184 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> current_pose_sub_;
185 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> guidance_state_sub_;
186
187 bool guidance_engaged_ = false;
188
191
194
195 // Unit test helper functions
197 void set_wm(carma_wm::WorldModelConstPtr new_wm) { wm_ = new_wm; }
198
199 // Unit Test Accessors
200 FRIEND_TEST(StopAndDwellStrategicPluginTest, findSpeedLimit);
201 FRIEND_TEST(StopAndDwellStrategicPluginTest, maneuvercbtest);
202};
203} // namespace stop_and_dwell_strategic_plugin
StrategicPlugin base class which can be extended by user provided plugins which wish to implement the...
FRIEND_TEST(StopAndDwellStrategicPluginTest, findSpeedLimit)
StopAndDwellStrategicPlugin(const rclcpp::NodeOptions &)
Default constructor for RouteFollowingPlugin class.
carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double current_dist, double end_dist, double start_speed, const lanelet::Id &starting_lane_id, const lanelet::Id &ending_lane_id, double stopping_accel, rclcpp::Time start_time, rclcpp::Time end_time) const
void guidance_state_cb(const carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback for the Guidance State.
std::string get_version_id()
Returns the version id of this plugin.
void plan_maneuvers_callback(std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
Service callback for arbitrator maneuver planning.
double findSpeedLimit(const lanelet::ConstLanelet &llt) const
Given a Lanelet, find it's associated Speed Limit.
carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....
VehicleState extractInitialState(const carma_planning_msgs::srv::PlanManeuvers::Request &req) const
Helper method to extract the initial vehicle state from the planning request method based on if the p...
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
carma_ros2_utils::CallbackReturn on_configure_plugin()
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
StopAndDwellStrategicPluginConfig config_
Config containing configurable algorithm parameters.
FRIEND_TEST(StopAndDwellStrategicPluginTest, maneuvercbtest)
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
std::vector< lanelet::ConstLanelet > getLaneletsBetweenWithException(double start_downtrack, double end_downtrack, bool shortest_path_only=false, bool bounds_inclusive=true) const
Helper method which calls carma_wm::WorldModel::getLaneletsBetween(start_downtrack,...
void currentPoseCb(geometry_msgs::msg::PoseStamped::UniquePtr msg)
callback function for current pose
carma_planning_msgs::msg::Maneuver composeLaneFollowingManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, rclcpp::Time start_time, double time_to_stop, std::vector< lanelet::Id > lane_ids)
Compose a lane keeping maneuver message based on input params.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > current_pose_sub_
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
Struct to store the configuration settings for the WzStrategicPlugin class.
Struct representing a vehicle state for the purposes of planning.