17#include <rclcpp/rclcpp.hpp> 
   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> 
   28#include <Eigen/Geometry> 
   36using oss = std::ostringstream;
 
   44                                          const std::string& plugin_name,
 
   46  : nh_(nh), wm_(wm), config_(config), debug_publisher_(debug_publisher), plugin_name_(plugin_name), version_id_ (
version_id)
 
   50  carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
 
   51  carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
 
   53  std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now();  
 
   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;
 
   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++)
 
   62    if(req->maneuver_plan.maneuvers[
i].type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING)
 
   64      maneuver_plan.push_back(req->maneuver_plan.maneuvers[
i]);
 
   65      resp->related_maneuvers.push_back((uint8_t)
i);
 
   91  RCLCPP_DEBUG_STREAM(
nh_->get_logger(), 
"points_and_target_speeds: " << points_and_target_speeds.size());
 
   93  RCLCPP_DEBUG_STREAM(
nh_->get_logger(), 
"PlanTrajectory");
 
   95  carma_planning_msgs::msg::TrajectoryPlan original_trajectory;
 
   96  original_trajectory.header.frame_id = 
"map";
 
   97  original_trajectory.header.stamp = 
nh_->now();
 
  103  original_trajectory.initial_longitudinal_velocity = std::max(req->vehicle_state.longitudinal_vel, 
config_.
minimum_speed);
 
  106  for (
auto& p : original_trajectory.trajectory_points) {
 
  110  resp->trajectory_plan = original_trajectory;
 
  119    RCLCPP_DEBUG(
nh_->get_logger(), 
"Ignored Object Avoidance");
 
  123    debug_msg_.trajectory_plan = resp->trajectory_plan;
 
  127  resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
 
  129  std::chrono::system_clock::time_point end_time = std::chrono::system_clock::now();  
 
  131  auto duration = end_time - start_time;
 
  133    rclcpp::get_logger(
"inlanecruising_plugin"),
 
  134    "ILC ExecutionTime: " << std::chrono::duration<double>(duration).count());
 
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.
 
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_
 
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
 
std::shared_ptr< const WorldModel > WorldModelConstPtr
 
std::function< void(const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds &)> DebugPublisher
 
Stuct containing the algorithm configuration values for the InLaneCruisingPlugin.
 
double buffer_ending_downtrack
 
int speed_moving_average_window_size
 
int turn_downsample_ratio
 
double lateral_accel_limit
 
double lat_accel_multiplier
 
double trajectory_time_length
 
double curve_resample_step_size
 
int curvature_moving_average_window_size
 
double max_accel_multiplier
 
int default_downsample_ratio
 
bool enable_object_avoidance
 
int tactical_plugin_service_call_timeout