20 namespace std_ph = std::placeholders;
56 auto error = update_params<double>(
69 auto error_2 = update_params<int>(
80 rcl_interfaces::msg::SetParametersResult result;
82 result.successful = !error && !error_2;
89 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"light_controlled_intersection_tactical_plugin"),
"LightControlledIntersectionTransitPluginNode trying to configure");
125 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"light_controlled_intersection_tactical_plugin"),
"Loaded params: " <<
config_);
130 yield_client_ = create_client<carma_planning_msgs::srv::PlanTrajectory>(
"yield_plugin/plan_trajectory");
132 RCLCPP_INFO(rclcpp::get_logger(
"light_controlled_intersection_tactical_plugin"),
"Yield Client Set");
135 return CallbackReturn::SUCCESS;
147 std::shared_ptr<rmw_request_id_t>,
148 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
149 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
151 worker_->planTrajectoryCB(req, resp);
156#include "rclcpp_components/register_node_macro.hpp"
std::string get_plugin_name() const
Return the name of this plugin.
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...
ROS node for the LightControlledIntersectionTransitPluginNode.
LightControlledIntersectionTransitPluginNode(const rclcpp::NodeOptions &)
LightControlledIntersectionTransitPluginNode constructor.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
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...
std::string get_version_id() override
Returns the version id of this plugin.
std::shared_ptr< LightControlledIntersectionTacticalPlugin > worker_
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
Stuct containing the algorithm configuration values for light_controlled_intersection_tactical_plugin...
int curvature_moving_average_window_size
int turn_downsample_ratio
double lateral_accel_limit
double buffer_ending_downtrack
double curve_resample_step_size
double lat_accel_multiplier
double centerline_sampling_spacing
double algorithm_evaluation_period
bool enable_object_avoidance
int default_downsample_ratio
double trajectory_time_length
double algorithm_evaluation_distance
int speed_moving_average_window_size
double vehicle_accel_limit_multiplier
double vehicle_accel_limit
double vehicle_decel_limit
int tactical_plugin_service_call_timeout
double vehicle_decel_limit_multiplier