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.
|
#include <stop_and_wait_plugin.hpp>
Public Member Functions | |
StopandWait (std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh, carma_wm::WorldModelConstPtr wm, const StopandWaitConfig &config, const std::string &plugin_name, const std::string &version_id) | |
Constructor. More... | |
bool | plan_trajectory_cb (carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) |
Service callback for trajectory planning. More... | |
std::vector< PointSpeedPair > | maneuvers_to_points (const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &state) |
Converts a set of requested STOP_AND_WAIT maneuvers to point speed limit pairs. More... | |
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > | compose_trajectory_from_centerline (const std::vector< PointSpeedPair > &points, double starting_downtrack, double starting_speed, double stop_location, double stop_location_buffer, rclcpp::Time start_time, double stopping_acceleration, double &initial_speed) |
Method converts a list of lanelet centerline points and current vehicle state into a usable list of trajectory points for trajectory planning. More... | |
void | splitPointSpeedPairs (const std::vector< PointSpeedPair > &points, std::vector< lanelet::BasicPoint2d > *basic_points, std::vector< double > *speeds) const |
Helper method to split a list of PointSpeedPair into separate point and speed lists. More... | |
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > | trajectory_from_points_times_orientations (const std::vector< lanelet::BasicPoint2d > &points, const std::vector< double > ×, const std::vector< double > &yaws, rclcpp::Time startTime) |
void | set_yield_client (carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client) |
set the yield service More... | |
Private Attributes | |
double | epsilon_ = 0.001 |
std::string | plugin_name_ |
std::string | version_id_ |
carma_wm::WorldModelConstPtr | wm_ |
StopandWaitConfig | config_ |
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > | nh_ |
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > | yield_client_ |
Definition at line 50 of file stop_and_wait_plugin.hpp.
stop_and_wait_plugin::StopandWait::StopandWait | ( | std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > | nh, |
carma_wm::WorldModelConstPtr | wm, | ||
const StopandWaitConfig & | config, | ||
const std::string & | plugin_name, | ||
const std::string & | version_id | ||
) |
Constructor.
Definition at line 51 of file stop_and_wait_plugin.cpp.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > stop_and_wait_plugin::StopandWait::compose_trajectory_from_centerline | ( | const std::vector< PointSpeedPair > & | points, |
double | starting_downtrack, | ||
double | starting_speed, | ||
double | stop_location, | ||
double | stop_location_buffer, | ||
rclcpp::Time | start_time, | ||
double | stopping_acceleration, | ||
double & | initial_speed | ||
) |
Method converts a list of lanelet centerline points and current vehicle state into a usable list of trajectory points for trajectory planning.
points | The set of points that define the current lane the vehicle is in and are defined based on the request planning maneuvers. These points must be in the same lane as the vehicle and must extend in front of it though it is fine if they also extend behind it. |
state | The current state of the vehicle |
initial_speed | Returns the initial_speed used to generate the trajectory |
Definition at line 233 of file stop_and_wait_plugin.cpp.
References StopandWaitConfig::accel_limit_multiplier, carma_wm::geometry::compute_tangent_orientations(), config_, StopandWaitConfig::crawl_speed, process_bag::i, StopandWaitConfig::minimal_trajectory_duration, basic_autonomy::smoothing::moving_average_filter(), StopandWaitConfig::moving_average_window_size, plugin_name_, stop_and_wait_plugin::PointSpeedPair::point, stop_and_wait_plugin::PointSpeedPair::speed, splitPointSpeedPairs(), StopandWaitConfig::stop_timestep, and trajectory_from_points_times_orientations().
Referenced by plan_trajectory_cb().
std::vector< PointSpeedPair > stop_and_wait_plugin::StopandWait::maneuvers_to_points | ( | const std::vector< carma_planning_msgs::msg::Maneuver > & | maneuvers, |
const carma_wm::WorldModelConstPtr & | wm, | ||
const carma_planning_msgs::msg::VehicleState & | state | ||
) |
Converts a set of requested STOP_AND_WAIT maneuvers to point speed limit pairs.
maneuvers | The list of maneuvers to convert |
max_starting_downtrack | The maximum downtrack that is allowed for the first maneuver. This should be set to the vehicle position or earlier. If the first maneuver exceeds this then it's downtrack will be shifted to this value. |
ASSUMPTION: Since the vehicle is trying to stop the assumption made is that the speed limit is irrelevant. ASSUMPTION: The provided maneuver lies on the route shortest path
Definition at line 169 of file stop_and_wait_plugin.cpp.
References StopandWaitConfig::centerline_sampling_spacing, config_, stop_and_wait_plugin::PointSpeedPair::point, stop_and_wait_plugin::PointSpeedPair::speed, and wm_.
Referenced by plan_trajectory_cb().
bool stop_and_wait_plugin::StopandWait::plan_trajectory_cb | ( | carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr | req, |
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr | resp | ||
) |
Service callback for trajectory planning.
req | The service request |
resp | The service response |
Definition at line 59 of file stop_and_wait_plugin.cpp.
References compose_trajectory_from_centerline(), config_, StopandWaitConfig::default_stopping_buffer, StopandWaitConfig::enable_object_avoidance, epsilon_, maneuvers_to_points(), basic_autonomy::waypoint_generation::modify_trajectory_to_yield_to_obstacles(), nh_, StopandWaitConfig::tactical_plugin_service_call_timeout, carma_cooperative_perception::to_string(), wm_, and yield_client_.
void stop_and_wait_plugin::StopandWait::set_yield_client | ( | carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > | client | ) |
set the yield service
yield_srv | input yield service |
Definition at line 421 of file stop_and_wait_plugin.cpp.
References yield_client_.
void stop_and_wait_plugin::StopandWait::splitPointSpeedPairs | ( | const std::vector< PointSpeedPair > & | points, |
std::vector< lanelet::BasicPoint2d > * | basic_points, | ||
std::vector< double > * | speeds | ||
) | const |
Helper method to split a list of PointSpeedPair into separate point and speed lists.
Definition at line 407 of file stop_and_wait_plugin.cpp.
Referenced by compose_trajectory_from_centerline().
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > stop_and_wait_plugin::StopandWait::trajectory_from_points_times_orientations | ( | const std::vector< lanelet::BasicPoint2d > & | points, |
const std::vector< double > & | times, | ||
const std::vector< double > & | yaws, | ||
rclcpp::Time | startTime | ||
) |
Definition at line 204 of file stop_and_wait_plugin.cpp.
References process_bag::i, and plugin_name_.
Referenced by compose_trajectory_from_centerline().
|
private |
Definition at line 127 of file stop_and_wait_plugin.hpp.
Referenced by compose_trajectory_from_centerline(), maneuvers_to_points(), and plan_trajectory_cb().
|
private |
Definition at line 121 of file stop_and_wait_plugin.hpp.
Referenced by plan_trajectory_cb().
|
private |
Definition at line 128 of file stop_and_wait_plugin.hpp.
Referenced by plan_trajectory_cb().
|
private |
Definition at line 124 of file stop_and_wait_plugin.hpp.
Referenced by compose_trajectory_from_centerline(), and trajectory_from_points_times_orientations().
|
private |
Definition at line 125 of file stop_and_wait_plugin.hpp.
|
private |
Definition at line 126 of file stop_and_wait_plugin.hpp.
Referenced by maneuvers_to_points(), and plan_trajectory_cb().
|
private |
Definition at line 130 of file stop_and_wait_plugin.hpp.
Referenced by plan_trajectory_cb(), and set_yield_client().