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.
pure_pursuit_wrapper.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018-2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
18#include <trajectory_utils/conversions/conversions.hpp>
19#include <carma_wm/Geometry.hpp>
20#include <algorithm>
21
22
24{
25namespace std_ph = std::placeholders;
26
27PurePursuitWrapperNode::PurePursuitWrapperNode(const rclcpp::NodeOptions& options)
28 : carma_guidance_plugins::ControlPlugin(options)
29{
31 config_.vehicle_response_lag = declare_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
32 config_.minimum_lookahead_distance = declare_parameter<double>("minimum_lookahead_distance", config_.minimum_lookahead_distance);
33 config_.maximum_lookahead_distance = declare_parameter<double>("maximum_lookahead_distance", config_.maximum_lookahead_distance);
34 config_.speed_to_lookahead_ratio = declare_parameter<double>("speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio);
35 config_.is_interpolate_lookahead_point = declare_parameter<bool>("is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point);
36 config_.is_delay_compensation = declare_parameter<bool>("is_delay_compensation", config_.is_delay_compensation);
37 config_.emergency_stop_distance = declare_parameter<double>("emergency_stop_distance", config_.emergency_stop_distance);
38 config_.speed_thres_traveling_direction = declare_parameter<double>("speed_thres_traveling_direction", config_.speed_thres_traveling_direction);
39 config_.dist_front_rear_wheels = declare_parameter<double>("dist_front_rear_wheels", config_.dist_front_rear_wheels);
40
41 // integrator part
42 config_.dt = declare_parameter<double>("dt", config_.dt);
43 config_.integrator_max_pp = declare_parameter<double>("integrator_max_pp", config_.integrator_max_pp);
44 config_.integrator_min_pp = declare_parameter<double>("integrator_min_pp", config_.integrator_min_pp);
45 config_.Ki_pp = declare_parameter<double>("Ki_pp", config_.Ki_pp);
46 config_.is_integrator_enabled = declare_parameter<bool>("is_integrator_enabled", config_.is_integrator_enabled);
47}
48
49carma_ros2_utils::CallbackReturn PurePursuitWrapperNode::on_configure_plugin()
50{
52 get_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
53 get_parameter<double>("minimum_lookahead_distance", config_.minimum_lookahead_distance);
54 get_parameter<double>("maximum_lookahead_distance", config_.maximum_lookahead_distance);
55 get_parameter<double>("speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio);
56 get_parameter<bool>("is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point);
57 get_parameter<bool>("is_delay_compensation", config_.is_delay_compensation);
58 get_parameter<double>("emergency_stop_distance", config_.emergency_stop_distance);
59 get_parameter<double>("speed_thres_traveling_direction", config_.speed_thres_traveling_direction);
60 get_parameter<double>("dist_front_rear_wheels", config_.dist_front_rear_wheels);
61
62 // integrator configs
63 get_parameter<double>("dt", config_.dt);
64 get_parameter<double>("integrator_max_pp", config_.integrator_max_pp);
65 get_parameter<double>("integrator_min_pp", config_.integrator_min_pp);
66 get_parameter<double>("Ki_pp", config_.Ki_pp);
67 get_parameter<bool>("is_integrator_enabled", config_.is_integrator_enabled);
68
69 RCLCPP_INFO_STREAM(rclcpp::get_logger("pure_pursuit_wrapper"), "Loaded Params: " << config_);
70
71 // Register runtime parameter update callback
72 add_on_set_parameters_callback(std::bind(&PurePursuitWrapperNode::parameter_update_callback, this, std_ph::_1));
73
74 // create config for pure_pursuit worker
75 pure_pursuit::Config cfg{
84 };
85
86 pure_pursuit::IntegratorConfig i_cfg;
87 i_cfg.dt = config_.dt;
88 i_cfg.integrator_max_pp = config_.integrator_max_pp;
89 i_cfg.integrator_min_pp = config_.integrator_min_pp;
90 i_cfg.Ki_pp = config_.Ki_pp;
91 i_cfg.integral = 0.0; // accumulator of integral starts from 0
92 i_cfg.is_integrator_enabled = config_.is_integrator_enabled;
93
94 pp_ = std::make_shared<pure_pursuit::PurePursuit>(cfg, i_cfg);
95
96 // Return success if everything initialized successfully
97 return CallbackReturn::SUCCESS;
98}
99
100motion::motion_common::State PurePursuitWrapperNode::convert_state(geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist)
101{
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;
109
110 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
111 return state;
112}
113
114autoware_msgs::msg::ControlCommandStamped PurePursuitWrapperNode::convert_cmd(motion::motion_common::Command cmd)
115{
116 autoware_msgs::msg::ControlCommandStamped return_cmd;
117 return_cmd.header.stamp = cmd.stamp;
118
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;
122
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);
128
129 return return_cmd;
130}
131
132autoware_msgs::msg::ControlCommandStamped PurePursuitWrapperNode::generate_command()
133{
134 // process and save the trajectory inside pure_pursuit
135 autoware_msgs::msg::ControlCommandStamped converted_cmd;
136
138 return converted_cmd;
139
140 motion::control::controller_common::State state_tf = convert_state(current_pose_.get(), current_twist_.get());
141
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);
143
144 current_trajectory_.get().header.frame_id = state_tf.header.frame_id;
145
147
148 pp_->set_trajectory(autoware_traj_plan);
149
150 const auto cmd{pp_->compute_command(state_tf)};
151
152 converted_cmd = convert_cmd(cmd);
153
154
155 return converted_cmd;
156}
157
158rcl_interfaces::msg::SetParametersResult PurePursuitWrapperNode::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
159{
160 auto error_double = update_params<double>({
161 {"vehicle_response_lag", config_.vehicle_response_lag},
162 {"minimum_lookahead_distance", config_.minimum_lookahead_distance},
163 {"maximum_lookahead_distance", config_.maximum_lookahead_distance},
164 {"speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio},
165 {"emergency_stop_distance", config_.emergency_stop_distance},
166 {"speed_thres_traveling_direction", config_.speed_thres_traveling_direction},
167 {"dist_front_rear_wheels", config_.dist_front_rear_wheels},
168 {"integrator_max_pp", config_.integrator_max_pp},
169 {"integrator_min_pp", config_.integrator_min_pp},
170 {"Ki_pp", config_.Ki_pp},
171 }, parameters);
172
173 auto error_bool = update_params<bool>({
174 {"is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point},
175 {"is_delay_compensation", config_.is_delay_compensation},
176 {"is_integrator_enabled", config_.is_integrator_enabled}
177 }, parameters);
178
179 rcl_interfaces::msg::SetParametersResult result;
180
181 result.successful = !error_double && !error_bool;
182
183 return result;
184}
185
186
188{
189 return true;
190}
191
193{
194 return "v4.0";
195}
196
197std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> PurePursuitWrapperNode::remove_repeated_timestamps(const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& traj_points)
198{
199
200 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> new_traj_points;
201
202 carma_planning_msgs::msg::TrajectoryPlanPoint prev_point;
203 bool first = true;
204
205 for(auto point : traj_points){
206
207 if(first){
208 first = false;
209 prev_point = point;
210 new_traj_points.push_back(point);
211 continue;
212 }
213
214 if(point.target_time != prev_point.target_time){
215 new_traj_points.push_back(point);
216 prev_point = point;
217 }
218 else{
219 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("pure_pursuit_wrapper"), "Duplicate point found");
220 }
221 }
222
223 return new_traj_points;
224
225}
226
227} // namespace pure_pursuit_wrapper
228
229#include "rclcpp_components/register_node_macro.hpp"
230
231// Register the component with class_loader
232RCLCPP_COMPONENTS_REGISTER_NODE(pure_pursuit_wrapper::PurePursuitWrapperNode)
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.
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 > &parameters)
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
Definition: utm_zone.cpp:21
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig.