18#include <trajectory_utils/conversions/conversions.hpp>
25namespace std_ph = std::placeholders;
69 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"Loaded Params: " <<
config_);
75 pure_pursuit::Config cfg{
86 pure_pursuit::IntegratorConfig i_cfg;
94 pp_ = std::make_shared<pure_pursuit::PurePursuit>(cfg, i_cfg);
97 return CallbackReturn::SUCCESS;
102 motion::motion_common::State state;
103 state.header = pose.header;
104 state.state.x = pose.pose.position.x;
105 state.state.y = pose.pose.position.y;
106 state.state.z = pose.pose.position.z;
107 state.state.heading.real = pose.pose.orientation.w;
108 state.state.heading.imag = pose.pose.orientation.z;
110 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
116 autoware_msgs::msg::ControlCommandStamped return_cmd;
117 return_cmd.header.stamp = cmd.stamp;
119 return_cmd.cmd.linear_acceleration = cmd.long_accel_mps2;
120 return_cmd.cmd.linear_velocity = cmd.velocity_mps;
121 return_cmd.cmd.steering_angle = cmd.front_wheel_angle_rad;
123 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"generate_command() cmd.stamp: " <<
std::to_string(rclcpp::Time(cmd.stamp).seconds()));
124 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"generate_command() cmd.long_accel_mps2: " << cmd.long_accel_mps2);
125 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"generate_command() cmd.velocity_mps: " << cmd.velocity_mps);
126 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"generate_command() cmd.rear_wheel_angle_rad: " << cmd.rear_wheel_angle_rad);
127 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"generate_command() cmd.front_wheel_angle_rad: " << cmd.front_wheel_angle_rad);
135 autoware_msgs::msg::ControlCommandStamped converted_cmd;
138 return converted_cmd;
142 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"Forced from frame_id: " << state_tf.header.frame_id <<
", into: " <<
current_trajectory_.get().header.frame_id);
148 pp_->set_trajectory(autoware_traj_plan);
150 const auto cmd{
pp_->compute_command(state_tf)};
155 return converted_cmd;
160 auto error_double = update_params<double>({
173 auto error_bool = update_params<bool>({
179 rcl_interfaces::msg::SetParametersResult result;
181 result.successful = !error_double && !error_bool;
200 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> new_traj_points;
202 carma_planning_msgs::msg::TrajectoryPlanPoint prev_point;
205 for(
auto point : traj_points){
210 new_traj_points.push_back(
point);
214 if(
point.target_time != prev_point.target_time){
215 new_traj_points.push_back(
point);
219 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"pure_pursuit_wrapper"),
"Duplicate point found");
223 return new_traj_points;
229#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.
PurePursuitWrapperConfig config_
std::shared_ptr< pure_pursuit::PurePursuit > pp_
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
autoware_msgs::msg::ControlCommandStamped convert_cmd(motion::motion_common::Command cmd)
motion::motion_common::State convert_state(geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist)
std::string get_version_id() override
Returns the version id of this plugin.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > remove_repeated_timestamps(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &traj_points)
Drops any points that sequentially have same target_time and return new trajectory_points in order to...
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.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Example callback for dynamic parameter updates.
PurePursuitWrapperNode(const rclcpp::NodeOptions &options)
Constructor.
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 ...
auto to_string(const UtmZone &zone) -> std::string
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig.
double vehicle_response_lag
double dist_front_rear_wheels
double emergency_stop_distance
double minimum_lookahead_distance
bool is_interpolate_lookahead_point
double speed_thres_traveling_direction
double speed_to_lookahead_ratio
bool is_delay_compensation
double maximum_lookahead_distance
bool is_integrator_enabled