20 namespace std_ph = std::placeholders;
59 auto error = update_params<std::string>(
63 auto error_2 = update_params<double>(
84 auto error_3 = update_params<int>(
91 rcl_interfaces::msg::SetParametersResult result;
93 result.successful = !error && !error_2 && !error_3;
100 RCLCPP_INFO_STREAM(get_logger(),
"CooperativeLaneChangePlugin trying to configure");
136 RCLCPP_INFO_STREAM(get_logger(),
"Loaded params: " <<
config_);
139 pose_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>(
"current_pose", 1,
141 twist_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>(
"current_velocity", 1,
145 georeference_sub_ = create_subscription<std_msgs::msg::String>(
"georeference", 1,
147 bsm_sub_ = create_subscription<carma_v2x_msgs::msg::BSM>(
"bsm_outbound", 1,
152 lanechange_status_pub_ = create_publisher<carma_planning_msgs::msg::LaneChangeStatus>(
"cooperative_lane_change_status", 10);
158 return CallbackReturn::SUCCESS;
165 carma_planning_msgs::msg::LaneChangeStatus lc_status_msg;
169 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::ACCEPTANCE_RECEIVED;
170 lc_status_msg.description =
"Received lane merge acceptance";
175 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::REJECTION_RECEIVED;
176 lc_status_msg.description =
"Received lane merge rejection";
183 RCLCPP_DEBUG_STREAM(get_logger(),
"received mobility response is not related to CLC");
191 RCLCPP_DEBUG_STREAM(get_logger(),
"entered find_current_gap");
192 double current_gap = 0.0;
193 lanelet::BasicPoint2d ego_pos(ego_state.x_pos_global, ego_state.y_pos_global);
196 lanelet::LaneletMapConstPtr const_map(
wm_->getMap());
197 lanelet::ConstLanelet veh2_lanelet = const_map->laneletLayer.get(veh2_lanelet_id);
198 RCLCPP_DEBUG_STREAM(get_logger(),
"veh2_lanelet id " << veh2_lanelet.id());
200 auto current_lanelets = lanelet::geometry::findNearest(const_map->laneletLayer, ego_pos, 10);
201 if(current_lanelets.size() == 0)
203 RCLCPP_WARN_STREAM(get_logger(),
"Cannot find any lanelet in map!");
206 lanelet::ConstLanelet current_lanelet = current_lanelets[0].second;
207 RCLCPP_DEBUG_STREAM(get_logger(),
"current llt id " << current_lanelet.id());
210 lanelet::ConstLanelet start_lanelet = veh2_lanelet;
211 lanelet::ConstLanelet end_lanelet = current_lanelet;
213 auto map_graph =
wm_->getMapRoutingGraph();
214 RCLCPP_DEBUG_STREAM(get_logger(),
"Graph created");
216 auto temp_route = map_graph->getRoute(start_lanelet, end_lanelet);
217 RCLCPP_DEBUG_STREAM(get_logger(),
"Route created");
220 lanelet::routing::LaneletPath shortest_path2;
223 shortest_path2 = temp_route.get().shortestPath();
226 RCLCPP_ERROR_STREAM(get_logger(),
"No path exists from roadway object to subject");
227 throw std::invalid_argument(
"No path exists from roadway object to subject");
230 RCLCPP_DEBUG_STREAM(get_logger(),
"Shorted path created size: " << shortest_path2.size());
231 for (
auto llt : shortest_path2)
233 RCLCPP_DEBUG_STREAM(get_logger(),
"llt id route: " << llt.id());
237 double veh1_current_downtrack =
wm_->routeTrackPos(ego_pos).downtrack;
238 RCLCPP_DEBUG_STREAM(get_logger(),
"ego_current_downtrack:" << veh1_current_downtrack);
240 current_gap = veh1_current_downtrack - veh2_downtrack;
241 RCLCPP_DEBUG_STREAM(get_logger(),
"Finding current gap");
242 RCLCPP_DEBUG_STREAM(get_logger(),
"Veh1 current downtrack: " << veh1_current_downtrack <<
" veh2 downtrack: " << veh2_downtrack);
263 std::shared_ptr<rmw_request_id_t>,
264 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
265 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
274 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan;
275 if(req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].type != carma_planning_msgs::msg::Maneuver::LANE_CHANGE)
277 throw std::invalid_argument (
"Cooperative Lane Change Plugin doesn't support this maneuver type");
279 maneuver_plan.push_back(req->maneuver_plan.maneuvers[req->maneuver_index_to_plan]);
282 long target_lanelet_id = stol(maneuver_plan[0].lane_change_maneuver.ending_lane_id);
283 double target_downtrack = maneuver_plan[0].lane_change_maneuver.end_dist;
286 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
287 double current_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
289 RCLCPP_DEBUG_STREAM(get_logger(),
"target_lanelet_id: " << target_lanelet_id);
290 RCLCPP_DEBUG_STREAM(get_logger(),
"target_downtrack: " << target_downtrack);
291 RCLCPP_DEBUG_STREAM(get_logger(),
"current_downtrack: " << current_downtrack);
292 RCLCPP_DEBUG_STREAM(get_logger(),
"Starting CLC downtrack: " << maneuver_plan[0].lane_change_maneuver.start_dist);
295 RCLCPP_DEBUG_STREAM(get_logger(),
"Lane change trajectory will not be planned. current_downtrack is more than " <<
config_.
starting_downtrack_range <<
" meters before starting CLC downtrack");
298 auto current_lanelets = lanelet::geometry::findNearest(
wm_->getMap()->laneletLayer, veh_pos, 10);
299 long current_lanelet_id = current_lanelets[0].second.id();
301 carma_planning_msgs::msg::LaneChangeStatus lc_status_msg;
302 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::PLANNING_SUCCESS;
307 long veh2_lanelet_id = 0;
308 double veh2_downtrack = 0.0, veh2_speed = 0.0;
309 bool foundRoadwayObject =
false;
310 bool negotiate =
true;
311 std::vector<carma_perception_msgs::msg::RoadwayObstacle> rwol =
wm_->getRoadwayObjects();
313 for(
int i = 0;
i < rwol.size();
i++){
314 if(rwol[
i].connected_vehicle_type.type == carma_perception_msgs::msg::ConnectedVehicleType::NOT_CONNECTED){
315 veh2_lanelet_id = rwol[0].lanelet_id;
316 veh2_downtrack = rwol[0].down_track;
317 veh2_speed = rwol[0].object.velocity.twist.linear.x;
318 foundRoadwayObject =
true;
322 if(foundRoadwayObject){
323 RCLCPP_DEBUG_STREAM(get_logger(),
"Found Roadway object");
325 RCLCPP_DEBUG_STREAM(get_logger(),
"veh2_lanelet_id: " << veh2_lanelet_id <<
", veh2_downtrack: " << veh2_downtrack);
327 double current_gap =
find_current_gap(veh2_lanelet_id, veh2_downtrack, req->vehicle_state);
328 RCLCPP_DEBUG_STREAM(get_logger(),
"Current gap: " << current_gap);
332 RCLCPP_DEBUG_STREAM(get_logger(),
"Relative velocity: " << relative_velocity);
334 RCLCPP_DEBUG_STREAM(get_logger(),
"Desired gap: " << desired_gap);
346 RCLCPP_DEBUG_STREAM(get_logger(),
"No roadway object");
351 RCLCPP_DEBUG_STREAM(get_logger(),
"Planning lane change trajectory");
353 std::string maneuver_id = maneuver_plan[0].lane_change_maneuver.parameters.maneuver_id;
356 RCLCPP_DEBUG_STREAM(get_logger(),
"Received maneuver id " << maneuver_id <<
" for the first time");
357 RCLCPP_DEBUG_STREAM(get_logger(),
"Original start dist is " << maneuver_plan[0].lane_change_maneuver.start_dist);
358 RCLCPP_DEBUG_STREAM(get_logger(),
"Original starting_lane_id is " << maneuver_plan[0].lane_change_maneuver.starting_lane_id);
374 RCLCPP_DEBUG_STREAM(get_logger(),
"Lane change maneuver " << maneuver_id <<
" has started, maintaining speed (in m/s): " <<
379 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> planned_trajectory_points =
plan_lanechange(req);
382 RCLCPP_DEBUG_STREAM(get_logger(),
"Negotiating");
385 carma_v2x_msgs::msg::MobilityRequest request =
create_mobility_request(planned_trajectory_points, maneuver_plan[0]);
391 carma_planning_msgs::msg::LaneChangeStatus lc_status_msg;
392 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::PLAN_SENT;
393 lc_status_msg.description =
"Requested lane merge";
399 RCLCPP_DEBUG_STREAM(get_logger(),
"negotiate:" << negotiate);
402 RCLCPP_DEBUG_STREAM(get_logger(),
"Adding to response");
411 rclcpp::Time planning_end_time = this->now();
414 carma_planning_msgs::msg::LaneChangeStatus lc_status_msg;
415 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::TIMED_OUT;
416 lc_status_msg.description =
"Request timed out for lane merge";
426 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp,
427 const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& planned_trajectory_points)
429 carma_planning_msgs::msg::TrajectoryPlan trajectory_plan;
430 trajectory_plan.header.frame_id =
"map";
431 trajectory_plan.header.stamp = this->now();
434 trajectory_plan.trajectory_points = planned_trajectory_points;
435 trajectory_plan.initial_longitudinal_velocity = std::max(req->vehicle_state.longitudinal_vel,
config_.
minimum_speed);
436 resp->trajectory_plan = trajectory_plan;
438 resp->related_maneuvers.push_back(req->maneuver_index_to_plan);
440 resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
445 carma_v2x_msgs::msg::MobilityRequest request_msg;
446 carma_v2x_msgs::msg::MobilityHeader header;
452 header.timestamp = rclcpp::Time(trajectory_plan.front().target_time).nanoseconds() * 1000000;
453 request_msg.m_header = header;
455 request_msg.strategy =
"carma/cooperative-lane-change";
456 request_msg.plan_type.type = carma_v2x_msgs::msg::PlanType::CHANGE_LANE_LEFT;
470 request_msg.urgency = urgency;
474 using boost::property_tree::ptree;
476 double end_speed_floor = std::floor(maneuver.lane_change_maneuver.end_speed);
477 int end_speed_fractional = (maneuver.lane_change_maneuver.end_speed - end_speed_floor) * 10;
479 RCLCPP_DEBUG_STREAM(get_logger(),
"end_speed_floor: " << end_speed_floor);
480 RCLCPP_DEBUG_STREAM(get_logger(),
"end_speed_fractional: " << end_speed_fractional);
481 RCLCPP_DEBUG_STREAM(get_logger(),
"start_lanelet_id: " << maneuver.lane_change_maneuver.starting_lane_id);
482 RCLCPP_DEBUG_STREAM(get_logger(),
"end_lanelet_id: " << maneuver.lane_change_maneuver.ending_lane_id);
484 pt.put(
"s",(
int)end_speed_floor);
485 pt.put(
"f",end_speed_fractional);
486 pt.put(
"sl",maneuver.lane_change_maneuver.starting_lane_id);
487 pt.put(
"el", maneuver.lane_change_maneuver.ending_lane_id);
489 std::stringstream body_stream;
490 boost::property_tree::json_parser::write_json(body_stream,pt);
491 request_msg.strategy_params = body_stream.str();
492 RCLCPP_DEBUG_STREAM(get_logger(),
"request_msg.strategy_params: " << request_msg.strategy_params);
495 carma_v2x_msgs::msg::Trajectory trajectory;
499 carma_planning_msgs::msg::TrajectoryPlanPoint temp_loc_to_convert;
500 temp_loc_to_convert.x =
pose_msg_.pose.position.x;
501 temp_loc_to_convert.y =
pose_msg_.pose.position.y;
505 location.timestamp = rclcpp::Time(trajectory_plan.front().target_time).nanoseconds() * 1000000;
507 request_msg.location = location;
511 RCLCPP_ERROR_STREAM(get_logger(),
"Map projection not available to be used with request message");
514 request_msg.trajectory = trajectory;
515 request_msg.expiration = rclcpp::Time(trajectory_plan.back().target_time).seconds();
516 RCLCPP_DEBUG_STREAM(get_logger(),
"request_msg.expiration: " << request_msg.expiration <<
" of which string size: " <<
std::to_string(request_msg.expiration).size());
523 carma_v2x_msgs::msg::Trajectory traj;
526 if (traj_points.size() < 2){
527 RCLCPP_WARN_STREAM(get_logger(),
"Received Trajectory Plan is too small");
531 carma_v2x_msgs::msg::LocationECEF prev_point = ecef_location;
532 for (
size_t i = 1;
i < traj_points.size();
i++){
534 carma_v2x_msgs::msg::LocationOffsetECEF offset;
536 offset.offset_x = (int16_t)(new_point.ecef_x - prev_point.ecef_x);
537 offset.offset_y = (int16_t)(new_point.ecef_y - prev_point.ecef_y);
538 offset.offset_z = (int16_t)(new_point.ecef_z - prev_point.ecef_z);
539 prev_point = new_point;
540 traj.offsets.push_back(offset);
544 traj.location = ecef_location;
552 throw std::invalid_argument(
"No map projector available for ecef conversion");
554 carma_v2x_msgs::msg::LocationECEF location;
556 lanelet::BasicPoint3d ecef_point =
map_projector_->projectECEF({traj_point.x, traj_point.y, 0.0}, 1);
557 location.ecef_x = ecef_point.x() * 100.0;
558 location.ecef_y = ecef_point.y() * 100.0;
559 location.ecef_z = ecef_point.z() * 100.0;
566 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
567 double current_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
570 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan;
571 if(req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].type != carma_planning_msgs::msg::Maneuver::LANE_CHANGE) {
572 throw std::invalid_argument (
"Cooperative Lane Change Plugin doesn't support this maneuver type");
574 maneuver_plan.push_back(req->maneuver_plan.maneuvers[req->maneuver_index_to_plan]);
576 if(current_downtrack >= maneuver_plan.front().lane_change_maneuver.end_dist){
592 RCLCPP_DEBUG_STREAM(get_logger(),
"Current downtrack: " << current_downtrack);
594 std::string maneuver_id = maneuver_plan.front().lane_change_maneuver.parameters.maneuver_id;
595 double original_start_dist = current_downtrack;
600 RCLCPP_DEBUG_STREAM(get_logger(),
"Maneuver id " << maneuver_id <<
" original start_dist is " << original_start_dist);
604 RCLCPP_DEBUG_STREAM(get_logger(),
"Updated maneuver id " << maneuver_id <<
" starting_lane_id to its original value of " <<
original_lc_maneuver_values_[maneuver_id].original_starting_lane_id);
609 RCLCPP_DEBUG_STREAM(get_logger(),
"Updating vehicle_state.longitudinal_vel to the initial lane change value of " <<
original_lc_maneuver_values_[maneuver_id].original_longitudinal_vel_ms);
613 RCLCPP_WARN_STREAM(get_logger(),
"No original values for lane change maneuver were found!");
616 double starting_downtrack = std::min(current_downtrack, original_start_dist);
621 auto maneuver_end_dist = maneuver_plan.back().lane_change_maneuver.end_dist;
622 auto maneuver_start_dist = maneuver_plan.front().lane_change_maneuver.start_dist;
625 RCLCPP_DEBUG_STREAM(get_logger(),
"Maneuvers to points size: " << points_and_target_speeds.size());
626 auto downsampled_points = carma_ros2_utils::containers::downsample_vector(points_and_target_speeds,
config_.
downsample_ratio);
630 RCLCPP_DEBUG_STREAM(get_logger(),
"Compose Trajectory size: " << trajectory_points.size());
631 return trajectory_points;
639 map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(msg->data.c_str());
645 std::string res =
"";
646 for (
size_t i = 0;
i < bsm_core.id.size();
i++){
662#include "rclcpp_components/register_node_macro.hpp"
virtual carma_wm::WorldModelConstPtr get_world_model() final
Method to return the default world model provided as a convience by this base class If this method or...
The class responsible for generating cooperative lanechange trajectories from received lane change ma...
carma_v2x_msgs::msg::LocationECEF trajectory_point_to_ecef(const carma_planning_msgs::msg::TrajectoryPlanPoint &traj_point) const
Converts Trajectory Point to ECEF frame using map projection.
geometry_msgs::msg::PoseStamped pose_msg_
std::string map_georeference_
carma_planning_msgs::msg::VehicleState ending_state_before_buffer_
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
carma_v2x_msgs::msg::MobilityRequest create_mobility_request(std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_plan, carma_planning_msgs::msg::Maneuver &maneuver)
Creates a mobility request message from planned trajectory and requested maneuver info.
void bsm_cb(const carma_v2x_msgs::msg::BSM::UniquePtr msg)
Callback for the BSM subscriber, which will store the latest BSM Core Data broadcasted by the host ve...
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > twist_sub_
void add_trajectory_to_response(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp, const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &planned_trajectory_points)
Adds the generated trajectory plan to the service response.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > plan_lanechange(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req)
Creates a vector of Trajectory Points from maneuver information in trajectory request.
void mobilityresponse_cb(const carma_v2x_msgs::msg::MobilityResponse::UniquePtr msg)
Callback to subscribed mobility response topic.
std::unordered_map< std::string, LaneChangeManeuverOriginalValues > original_lc_maneuver_values_
double find_current_gap(long veh2_lanelet_id, double veh2_downtrack, carma_planning_msgs::msg::VehicleState &ego_state) const
Calculates distance between subject vehicle and vehicle 2.
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t >, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override
Extending class provided callback which should return a planned trajectory based on the provided traj...
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::BSM > bsm_sub_
std::string bsmIDtoString(carma_v2x_msgs::msg::BSMCoreData bsm_core)
Method for extracting the BSM ID from a BSM Core Data object and converting it to a string.
CooperativeLaneChangePlugin(const rclcpp::NodeOptions &)
CooperativeLaneChangePlugin constructor.
carma_v2x_msgs::msg::BSMCoreData bsm_core_
bool is_lanechange_accepted_
void pose_cb(const geometry_msgs::msg::PoseStamped::UniquePtr msg)
Callback for the pose subscriber, which will store latest pose locally.
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_sub_
carma_wm::WorldModelConstPtr wm_
std::string get_version_id() override
Returns the version id of this plugin.
void twist_cb(const geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::LaneChangeStatus > lanechange_status_pub_
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityRequest > outgoing_mobility_request_pub_
std::string clc_request_id_
void georeference_cb(const std_msgs::msg::String::UniquePtr msg)
Callback for map projection string to define lat/lon -> map conversion.
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
carma_ros2_utils::CallbackReturn on_configure_plugin()
This method should be used to load parameters and will be called on the configure state transition.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_sub_
rclcpp::Time request_sent_time_
std::string DEFAULT_STRING_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityResponse > incoming_mobility_response_sub_
carma_v2x_msgs::msg::Trajectory trajectory_plan_to_trajectory(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &traj_points) const
Converts Trajectory Plan to (Mobility) Trajectory.
double maneuver_fraction_completed_
GeneralTrajConfig compose_general_trajectory_config(const std::string &trajectory_type, int default_downsample_ratio, int turn_downsample_ratio)
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_lanechange_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, const DetailedTrajConfig &detailed_config)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
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...
auto to_string(const UtmZone &zone) -> std::string
Stuct containing the algorithm configuration values for cooperative_lanechange.
double starting_downtrack_range
int speed_moving_average_window_size
double minimum_lookahead_distance
double curve_resample_step_size
double trajectory_time_length
double minimum_lookahead_speed
int curvature_moving_average_window_size
double maximum_lookahead_speed
int curvature_calc_lookahead_count
double lateral_accel_limit
std::string control_plugin_name
double maximum_lookahead_distance
int turn_downsample_ratio
double lanechange_time_out
double buffer_ending_downtrack
Convenience struct for storing the original start_dist and starting_lane_id associated with a receive...
double original_start_dist
std::string original_starting_lane_id