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::PurePursuitWrapperNode Class Reference

#include <pure_pursuit_wrapper.hpp>

Inheritance diagram for pure_pursuit_wrapper::PurePursuitWrapperNode:
Inheritance graph
Collaboration diagram for pure_pursuit_wrapper::PurePursuitWrapperNode:
Collaboration graph

Public Member Functions

 PurePursuitWrapperNode (const rclcpp::NodeOptions &options)
 Constructor. More...
 
autoware_msgs::msg::ControlCommandStamped generate_command () override
 Extending class provided method which should generate a command message which will be published to the required topic by the base class. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Example callback for dynamic parameter updates. More...
 
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. More...
 
bool get_availability () override
 Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes. More...
 
std::string get_version_id () override
 Returns the version id of this plugin. More...
 
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 avoid divide by zero situation. More...
 
motion::motion_common::State convert_state (geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist)
 
autoware_msgs::msg::ControlCommandStamped convert_cmd (motion::motion_common::Command cmd)
 
- Public Member Functions inherited from carma_guidance_plugins::ControlPlugin
 ControlPlugin (const rclcpp::NodeOptions &)
 ControlPlugin constructor. More...
 
virtual ~ControlPlugin ()=default
 Virtual destructor for safe deletion. More...
 
virtual autoware_msgs::msg::ControlCommandStamped generate_command ()=0
 Extending class provided method which should generate a command message which will be published to the required topic by the base class. More...
 
std::string get_capability () override
 Get the capability string representing this plugins capabilities Method must be overriden by extending classes. Expectation is that abstract plugin type parent classes will provide a default implementation. More...
 
uint8_t get_type () override final
 Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum. Extending classes for the specific type should override this method. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_deactivate (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_shutdown (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_error (const rclcpp_lifecycle::State &, const std::string &exception_string) override final
 
- Public Member Functions inherited from carma_guidance_plugins::PluginBaseNode
 PluginBaseNode (const rclcpp::NodeOptions &)
 PluginBaseNode constructor. More...
 
virtual ~PluginBaseNode ()=default
 Virtual destructor for safe deletion. More...
 
virtual std::shared_ptr< carma_wm::WMListenerget_world_model_listener () final
 Method to return the default world model listener provided as a convience by this base class If this method or get_world_model() are not called then the world model remains uninitialized and will not create unnecessary subscriptions. More...
 
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 get_world_model_listener() are not called then the world model remains uninitialized and will not create unnecessary subscriptions. More...
 
virtual bool get_activation_status () final
 Returns the activation status of this plugin. The plugins API callbacks will only be triggered when this method returns true. More...
 
virtual uint8_t get_type ()
 Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum. Extending classes for the specific type should override this method. More...
 
std::string get_plugin_name_and_ns () const
 Return the name of this plugin with namespace. NOTE: If only the name of the plugin is required, use get_plugin_name() More...
 
std::string get_plugin_name () const
 Return the name of this plugin. More...
 
virtual bool get_availability ()=0
 Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes. More...
 
virtual std::string get_capability ()=0
 Get the capability string representing this plugins capabilities Method must be overriden by extending classes. Expectation is that abstract plugin type parent classes will provide a default implementation. More...
 
virtual std::string get_version_id ()=0
 Returns the version id of this plugin. More...
 
virtual carma_ros2_utils::CallbackReturn on_configure_plugin ()=0
 Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states. This method should be used to load parameters and is required to be implemented. More...
 
virtual carma_ros2_utils::CallbackReturn on_activate_plugin ()
 Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states. This method should be used to prepare for future callbacks for plugin's capabilites. More...
 
virtual carma_ros2_utils::CallbackReturn on_deactivate_plugin ()
 Method which is triggered when this plugin is moved from the ACTIVE to INACTIVE states. This method should be used to disable any functionality which should cease execution when plugin is inactive. More...
 
virtual carma_ros2_utils::CallbackReturn on_cleanup_plugin ()
 Method which is triggered when this plugin is moved from the INACTIVE to UNCONFIGURED states. This method should be used to fully reset the plugin such that a future call to on_configure_plugin would leave the plugin in a fresh state as though just launched. More...
 
virtual carma_ros2_utils::CallbackReturn on_shutdown_plugin ()
 Method which is triggered when this plugin is moved from any state to FINALIZED This method should be used to generate any shutdown logs or final cleanup. More...
 
virtual carma_ros2_utils::CallbackReturn on_error_plugin (const std::string &exception_string)
 Method which is triggered when an unhandled exception occurs in this plugin This method should be used to cleanup such that the plugin could be moved to UNCONFIGURED state if possible. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_deactivate (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_shutdown (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_error (const rclcpp_lifecycle::State &, const std::string &exception_string) override
 
 FRIEND_TEST (carma_guidance_plugins_test, connections_test)
 

Private Member Functions

std::shared_ptr< pure_pursuit::PurePursuit > get_pure_pursuit_worker ()
 
 FRIEND_TEST (PurePursuitTest, sanity_check)
 

Private Attributes

PurePursuitWrapperConfig config_
 
std::shared_ptr< pure_pursuit::PurePursuit > pp_
 

Additional Inherited Members

- Protected Member Functions inherited from carma_guidance_plugins::ControlPlugin
void current_pose_callback (geometry_msgs::msg::PoseStamped::UniquePtr msg)
 
void current_twist_callback (geometry_msgs::msg::TwistStamped::UniquePtr msg)
 
virtual void current_trajectory_callback (carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
 Extending class provided method which can optionally handle trajectory plan callbacks. More...
 
- Protected Attributes inherited from carma_guidance_plugins::ControlPlugin
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
 The most recent pose message received by this node. More...
 
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
 The most recent velocity message received by this node. More...
 
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
 The most recent trajectory received by this plugin. More...
 

Detailed Description

Definition at line 37 of file pure_pursuit_wrapper.hpp.

Constructor & Destructor Documentation

◆ PurePursuitWrapperNode()

pure_pursuit_wrapper::PurePursuitWrapperNode::PurePursuitWrapperNode ( const rclcpp::NodeOptions &  options)
explicit

Constructor.

Definition at line 27 of file pure_pursuit_wrapper.cpp.

29{
30 config_ = PurePursuitWrapperConfig();
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}
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...

References config_, pure_pursuit_wrapper::PurePursuitWrapperConfig::dist_front_rear_wheels, pure_pursuit_wrapper::PurePursuitWrapperConfig::dt, pure_pursuit_wrapper::PurePursuitWrapperConfig::emergency_stop_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_max_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_min_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_delay_compensation, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_integrator_enabled, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_interpolate_lookahead_point, pure_pursuit_wrapper::PurePursuitWrapperConfig::Ki_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::maximum_lookahead_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::minimum_lookahead_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_thres_traveling_direction, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_to_lookahead_ratio, and pure_pursuit_wrapper::PurePursuitWrapperConfig::vehicle_response_lag.

Member Function Documentation

◆ convert_cmd()

autoware_msgs::msg::ControlCommandStamped pure_pursuit_wrapper::PurePursuitWrapperNode::convert_cmd ( motion::motion_common::Command  cmd)

Definition at line 114 of file pure_pursuit_wrapper.cpp.

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}
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

References carma_cooperative_perception::to_string().

Referenced by generate_command().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ convert_state()

motion::motion_common::State pure_pursuit_wrapper::PurePursuitWrapperNode::convert_state ( geometry_msgs::msg::PoseStamped  pose,
geometry_msgs::msg::TwistStamped  twist 
)

Definition at line 100 of file pure_pursuit_wrapper.cpp.

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}

Referenced by generate_command().

Here is the caller graph for this function:

◆ FRIEND_TEST()

pure_pursuit_wrapper::PurePursuitWrapperNode::FRIEND_TEST ( PurePursuitTest  ,
sanity_check   
)
private

◆ generate_command()

autoware_msgs::msg::ControlCommandStamped pure_pursuit_wrapper::PurePursuitWrapperNode::generate_command ( )
overridevirtual

Extending class provided method which should generate a command message which will be published to the required topic by the base class.

NOTE: Implementer can determine if trajectory has changed based on current_trajectory_->trajectory_id

Returns
The command message to publish

Implements carma_guidance_plugins::ControlPlugin.

Definition at line 132 of file pure_pursuit_wrapper.cpp.

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}
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 convert_cmd(motion::motion_common::Command cmd)
motion::motion_common::State convert_state(geometry_msgs::msg::PoseStamped pose, geometry_msgs::msg::TwistStamped twist)
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 ...

References config_, convert_cmd(), convert_state(), carma_guidance_plugins::ControlPlugin::current_pose_, carma_guidance_plugins::ControlPlugin::current_trajectory_, carma_guidance_plugins::ControlPlugin::current_twist_, pp_, basic_autonomy::waypoint_generation::process_trajectory_plan(), and pure_pursuit_wrapper::PurePursuitWrapperConfig::vehicle_response_lag.

Here is the call graph for this function:

◆ get_availability()

bool pure_pursuit_wrapper::PurePursuitWrapperNode::get_availability ( )
overridevirtual

Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes.

Returns
This method should return true if the plugin's current understanding of the world means it would be capable of planning or executing its capability.

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 187 of file pure_pursuit_wrapper.cpp.

188{
189 return true;
190}

◆ get_pure_pursuit_worker()

std::shared_ptr< pure_pursuit::PurePursuit > pure_pursuit_wrapper::PurePursuitWrapperNode::get_pure_pursuit_worker ( )
inlineprivate

Definition at line 82 of file pure_pursuit_wrapper.hpp.

83 {
84 return pp_;
85 }

References pp_.

◆ get_version_id()

std::string pure_pursuit_wrapper::PurePursuitWrapperNode::get_version_id ( )
overridevirtual

Returns the version id of this plugin.

Returns
The version id represented as a string

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 192 of file pure_pursuit_wrapper.cpp.

193{
194 return "v4.0";
195}

◆ on_configure_plugin()

carma_ros2_utils::CallbackReturn pure_pursuit_wrapper::PurePursuitWrapperNode::on_configure_plugin ( )
overridevirtual

This method should be used to load parameters and will be called on the configure state transition.

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 49 of file pure_pursuit_wrapper.cpp.

50{
51 config_ = PurePursuitWrapperConfig();
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}
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.

References config_, pure_pursuit_wrapper::PurePursuitWrapperConfig::dist_front_rear_wheels, pure_pursuit_wrapper::PurePursuitWrapperConfig::dt, pure_pursuit_wrapper::PurePursuitWrapperConfig::emergency_stop_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_max_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_min_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_delay_compensation, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_integrator_enabled, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_interpolate_lookahead_point, pure_pursuit_wrapper::PurePursuitWrapperConfig::Ki_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::maximum_lookahead_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::minimum_lookahead_distance, parameter_update_callback(), pp_, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_thres_traveling_direction, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_to_lookahead_ratio, and pure_pursuit_wrapper::PurePursuitWrapperConfig::vehicle_response_lag.

Here is the call graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult pure_pursuit_wrapper::PurePursuitWrapperNode::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Example callback for dynamic parameter updates.

Definition at line 158 of file pure_pursuit_wrapper.cpp.

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}

References config_, pure_pursuit_wrapper::PurePursuitWrapperConfig::dist_front_rear_wheels, pure_pursuit_wrapper::PurePursuitWrapperConfig::emergency_stop_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_max_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_min_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_delay_compensation, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_integrator_enabled, pure_pursuit_wrapper::PurePursuitWrapperConfig::is_interpolate_lookahead_point, pure_pursuit_wrapper::PurePursuitWrapperConfig::Ki_pp, pure_pursuit_wrapper::PurePursuitWrapperConfig::maximum_lookahead_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::minimum_lookahead_distance, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_thres_traveling_direction, pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_to_lookahead_ratio, and pure_pursuit_wrapper::PurePursuitWrapperConfig::vehicle_response_lag.

Referenced by on_configure_plugin().

Here is the caller graph for this function:

◆ remove_repeated_timestamps()

std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > pure_pursuit_wrapper::PurePursuitWrapperNode::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 avoid divide by zero situation.

Parameters
traj_pointsVelocity profile to shift. The first point should be the current vehicle speed

NOTE: This function assumes the target_time will not go backwards. In other words, it only removes "sequential" points that have same target_time

Returns
A new trajectory without any repeated time_stamps

Definition at line 197 of file pure_pursuit_wrapper.cpp.

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}

References process_traj_logs::point.

Member Data Documentation

◆ config_

PurePursuitWrapperConfig pure_pursuit_wrapper::PurePursuitWrapperNode::config_
private

◆ pp_

std::shared_ptr<pure_pursuit::PurePursuit> pure_pursuit_wrapper::PurePursuitWrapperNode::pp_
private

The documentation for this class was generated from the following files: