20 namespace std_ph = std::placeholders;
68 auto error_double = update_params<double>({
93 auto error_int = update_params<int>({
97 auto error_bool = update_params<bool>({
106 rcl_interfaces::msg::SetParametersResult result;
108 result.successful = !error_double && !error_int && !error_bool;
156 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"platooning_control"),
"Loaded Params: " <<
config_);
159 pure_pursuit::Config cfg{
170 pure_pursuit::IntegratorConfig i_cfg;
175 i_cfg.integral = 0.0;
178 pp_ = std::make_shared<pure_pursuit::PurePursuit>(cfg, i_cfg);
185 trajectory_plan_sub_ = create_subscription<carma_planning_msgs::msg::TrajectoryPlan>(
"platooning_control/plan_trajectory", 1,
193 platoon_info_pub_ = create_publisher<carma_planning_msgs::msg::PlatooningInfo>(
"platooning_info", 1);
197 return CallbackReturn::SUCCESS;
204 autoware_msgs::msg::ControlCommandStamped ctrl_msg;
211 double current_time_ms = this->now().nanoseconds() / 1e6;
216 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"returning due to timeout.");
225 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"returning due to first data input");
229 carma_planning_msgs::msg::TrajectoryPlanPoint second_trajectory_point =
current_trajectory_.get().trajectory_points[1];
249 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"Platoon leader leader id: " <<
platoon_leader_.
staticId);
251 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"Platoon leader leader cmd speed: " <<
platoon_leader_.
commandSpeed);
253 carma_planning_msgs::msg::PlatooningInfo platooning_info_msg = *msg;
255 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"platooning_info_msg.actual_gap: " << platooning_info_msg.actual_gap);
257 if (platooning_info_msg.actual_gap > 5.0)
259 platooning_info_msg.actual_gap -= 5.0;
262 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"platooning_info_msg.actual_gap: " << platooning_info_msg.actual_gap);
272 autoware_msgs::msg::ControlCommandStamped
PlatooningControlPlugin::generate_control_signals(
const carma_planning_msgs::msg::TrajectoryPlanPoint& first_trajectory_point,
const geometry_msgs::msg::PoseStamped& current_pose,
const geometry_msgs::msg::TwistStamped& current_twist)
279 motion::control::controller_common::State state_tf =
convert_state(current_pose, current_twist);
280 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"Forced from frame_id: " << state_tf.header.frame_id <<
", into: " <<
current_trajectory_.get().header.frame_id);
286 pp_->set_trajectory(autoware_traj_plan);
287 const auto cmd{
pp_->compute_command(state_tf)};
289 auto steer_cmd = cmd.front_wheel_angle_rad;
298 motion::motion_common::State state;
299 state.header = pose.header;
300 state.state.x = pose.pose.position.x;
301 state.state.y = pose.pose.position.y;
302 state.state.z = pose.pose.position.z;
303 state.state.heading.real = pose.pose.orientation.w;
304 state.state.heading.imag = pose.pose.orientation.z;
306 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
312 if (tp->trajectory_points.size() < 2) {
313 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"platooning_control"),
"PlatooningControlPlugin cannot execute trajectory as only 1 point was provided");
321 rclcpp::Time tp_time(tp->header.stamp);
322 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"tp header time = " << tp_time.nanoseconds() / 1000000);
327 geometry_msgs::msg::TwistStamped cmd_twist;
328 cmd_twist.twist.linear.x = linear_vel;
329 cmd_twist.twist.angular.z = angular_vel;
330 cmd_twist.header.stamp = this->now();
336 autoware_msgs::msg::ControlCommandStamped cmd_ctrl;
337 cmd_ctrl.header.stamp = this->now();
338 cmd_ctrl.cmd.linear_velocity = linear_vel;
339 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"ctrl command speed " << cmd_ctrl.cmd.linear_velocity);
340 cmd_ctrl.cmd.steering_angle = steering_angle;
341 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"ctrl command steering " << cmd_ctrl.cmd.steering_angle);
357 double trajectory_speed = 0;
359 double dx1 = trajectory_points[trajectory_points.size()-1].x - trajectory_points[0].x;
360 double dy1 = trajectory_points[trajectory_points.size()-1].y - trajectory_points[0].y;
361 double d1 = sqrt(dx1*dx1 + dy1*dy1);
362 double t1 = (rclcpp::Time((trajectory_points[trajectory_points.size()-1].target_time)).nanoseconds() - rclcpp::Time(trajectory_points[0].target_time).nanoseconds())/1e9;
364 double avg_speed = d1/t1;
365 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"trajectory_points size = " << trajectory_points.size() <<
", d1 = " << d1 <<
", t1 = " << t1 <<
", avg_speed = " << avg_speed);
367 for(
size_t i = 0;
i < trajectory_points.size() - 2;
i++ )
369 double dx = trajectory_points[
i + 1].x - trajectory_points[
i].x;
370 double dy = trajectory_points[
i + 1].y - trajectory_points[
i].y;
371 double d = sqrt(dx*dx + dy*dy);
372 double t = rclcpp::Time((trajectory_points[
i + 1].target_time)).seconds() - rclcpp::Time(trajectory_points[
i].target_time).seconds();
374 if(v > trajectory_speed)
376 trajectory_speed = v;
380 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"trajectory speed: " << trajectory_speed);
381 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platooning_control"),
"avg trajectory speed: " << avg_speed);
390#include "rclcpp_components/register_node_macro.hpp"
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
This class includes node-level logic for Platooning Control such as its publishers,...
motion::motion_common::State convert_state(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist) const
void platoon_info_cb(const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg)
callback function for platoon info
bool get_availability() override
Returns availability of plugin. Always true.
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.
void current_trajectory_callback(const carma_planning_msgs::msg::TrajectoryPlan::UniquePtr tp)
callback function for trajectory plan
double prev_input_time_ms_
double get_trajectory_speed(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_points)
calculate average speed of a set of trajectory points
geometry_msgs::msg::TwistStamped compose_twist_cmd(double linear_vel, double angular_vel)
Compose twist message from linear and angular velocity commands.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
std::string get_version_id() override
Returns version id of plugn.
PlatooningControlWorker pcw_
autoware_msgs::msg::ControlCommandStamped compose_ctrl_cmd(double linear_vel, double steering_angle)
Compose control message from speed and steering commands.
PlatoonLeaderInfo platoon_leader_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_sub_
autoware_msgs::msg::ControlCommandStamped generate_control_signals(const carma_planning_msgs::msg::TrajectoryPlanPoint &first_trajectory_point, const geometry_msgs::msg::PoseStamped ¤t_pose, const geometry_msgs::msg::TwistStamped ¤t_twist)
generate control signal by calculating speed and steering commands.
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
long consecutive_input_counter_
std::shared_ptr< pure_pursuit::PurePursuit > pp_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_pub_
PlatooningControlPluginConfig config_
PlatooningControlPlugin(const rclcpp::NodeOptions &options)
PlatooningControlPlugin constructor.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > trajectory_plan_sub_
This is the worker class for platoon controller. It is responsible for generating and smoothing the s...
void set_leader(const PlatoonLeaderInfo &leader)
Sets the platoon leader object using info from msg.
void set_current_speed(double speed)
set current speed
std::shared_ptr< PlatooningControlPluginConfig > ctrl_config_
void generate_speed(const carma_planning_msgs::msg::TrajectoryPlanPoint &point)
Generates speed commands (in m/s) based on the trajectory point.
autoware_auto_msgs::msg::Trajectory process_trajectory_plan(const carma_planning_msgs::msg::TrajectoryPlan &tp, double vehicle_response_lag)
Given a carma type of trajectory_plan, generate autoware type of trajectory accounting for speed_lag ...
int NumberOfVehicleInFront
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.
double emergency_stop_distance
bool is_interpolate_lookahead_point
double speed_thres_traveling_direction
double min_delta_speed_per_timestep
double max_lookahead_dist
double stand_still_headway_m
double adjustment_cap_mps
double max_delta_speed_per_timestep
int ignore_initial_inputs
double dist_front_rear_wheels
bool is_integrator_enabled
double vehicle_response_lag
double min_lookahead_dist
bool is_delay_compensation
double speed_to_lookahead_ratio
bool enable_max_accel_filter
bool enable_max_adjustment_filter