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.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 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 <rclcpp/rclcpp.hpp>
18#include <string>
19#include <algorithm>
20#include <memory>
21#include <boost/uuid/uuid_generators.hpp>
22#include <boost/uuid/uuid_io.hpp>
23#include <lanelet2_core/geometry/Point.h>
24#include <trajectory_utils/trajectory_utils.hpp>
25#include <trajectory_utils/conversions/conversions.hpp>
26#include <sstream>
27#include <Eigen/Core>
28#include <Eigen/Geometry>
29#include <Eigen/LU>
30#include <Eigen/SVD>
32
33
34
35
36using oss = std::ostringstream;
37
39{
40InLaneCruisingPlugin::InLaneCruisingPlugin(std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh,
42 const InLaneCruisingPluginConfig& config,
43 const DebugPublisher& debug_publisher,
44 const std::string& plugin_name,
45 const std::string& version_id)
46 : nh_(nh), wm_(wm), config_(config), debug_publisher_(debug_publisher), plugin_name_(plugin_name), version_id_ (version_id)
47{}
48
50 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
51 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
52{
53 std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now(); // Start timing the execution time for planning so it can be logged
54
55 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
56 double current_downtrack = wm_->routeTrackPos(veh_pos).downtrack;
57
58 // Only plan the trajectory for the initial LANE_FOLLOWING maneuver and any immediately sequential maneuvers of the same type
59 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan;
60 for(size_t i = req->maneuver_index_to_plan; i < req->maneuver_plan.maneuvers.size(); i++)
61 {
62 if(req->maneuver_plan.maneuvers[i].type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING)
63 {
64 maneuver_plan.push_back(req->maneuver_plan.maneuvers[i]);
65 resp->related_maneuvers.push_back((uint8_t)i);
66 }
67 else
68 {
69 break;
70 }
71 }
72
75
79
87
88 auto points_and_target_speeds = basic_autonomy::waypoint_generation::create_geometry_profile(maneuver_plan, std::max((double)0, current_downtrack - config_.back_distance),
89 wm_, ending_state_before_buffer_, req->vehicle_state, wpg_general_config, wpg_detail_config);
90
91 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "points_and_target_speeds: " << points_and_target_speeds.size());
92
93 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "PlanTrajectory");
94
95 carma_planning_msgs::msg::TrajectoryPlan original_trajectory;
96 original_trajectory.header.frame_id = "map";
97 original_trajectory.header.stamp = nh_->now();
98 original_trajectory.trajectory_id = boost::uuids::to_string(boost::uuids::random_generator()());
99
100 original_trajectory.trajectory_points = basic_autonomy:: waypoint_generation::compose_lanefollow_trajectory_from_path(points_and_target_speeds,
101 req->vehicle_state, req->header.stamp, wm_, ending_state_before_buffer_, debug_msg_,
102 wpg_detail_config); // Compute the trajectory
103 original_trajectory.initial_longitudinal_velocity = std::max(req->vehicle_state.longitudinal_vel, config_.minimum_speed);
104
105 // Set the planning plugin field name
106 for (auto& p : original_trajectory.trajectory_points) {
107 p.planner_plugin_name = plugin_name_;
108 }
109
110 resp->trajectory_plan = original_trajectory;
111
112 // Aside from the flag, ILC should not call yield_plugin on invalid trajectories
113 if (config_.enable_object_avoidance && original_trajectory.trajectory_points.size() >= 2)
114 {
116 }
117 else
118 {
119 RCLCPP_DEBUG(nh_->get_logger(), "Ignored Object Avoidance");
120 }
121
122 if (config_.publish_debug) { // Publish the debug message if in debug logging mode
123 debug_msg_.trajectory_plan = resp->trajectory_plan;
125 }
126
127 resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
128
129 std::chrono::system_clock::time_point end_time = std::chrono::system_clock::now(); // Planning complete
130
131 auto duration = end_time - start_time;
132 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "ExecutionTime: " << std::chrono::duration<double>(duration).count());
133}
134
135void InLaneCruisingPlugin::set_yield_client(carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> client)
136{
137 yield_client_ = client;
138}
139
140
141} // namespace inlanecruising_plugin
void set_yield_client(carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client)
set the yield service
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::ostringstream oss
GeneralTrajConfig compose_general_trajectory_config(const std::string &trajectory_type, int default_downsample_ratio, int turn_downsample_ratio)
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr modify_trajectory_to_yield_to_obstacles(const std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > &node_handler, const carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr &req, const carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &resp, const carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > &yield_client, int yield_plugin_service_call_timeout)
Applies a yield trajectory to the original trajectory set in response.
DetailedTrajConfig compose_detailed_trajectory_config(double trajectory_time_length, double curve_resample_step_size, double minimum_speed, double max_accel, double lateral_accel_limit, int speed_moving_average_window_size, int curvature_moving_average_window_size, double back_distance, double buffer_ending_downtrack, std::string desired_controller_plugin="default")
std::vector< PointSpeedPair > create_geometry_profile(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, double max_starting_downtrack, const carma_wm::WorldModelConstPtr &wm, carma_planning_msgs::msg::VehicleState &ending_state_before_buffer, const carma_planning_msgs::msg::VehicleState &state, const GeneralTrajConfig &general_config, const DetailedTrajConfig &detailed_config)
Creates geometry profile to return a point speed pair struct for LANE FOLLOW and LANE CHANGE maneuver...
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_lanefollow_trajectory_from_path(const std::vector< PointSpeedPair > &points, const carma_planning_msgs::msg::VehicleState &state, const rclcpp::Time &state_time, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &ending_state_before_buffer, carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds &debug_msg, const DetailedTrajConfig &detailed_config)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
std::function< void(const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds &)> DebugPublisher
string version_id
Stuct containing the algorithm configuration values for the InLaneCruisingPlugin.