A path smoother implementation.
More...
#include <nav2_smoother/include/nav2_smoother/simple_smoother.hpp>
|
void | smoothImpl (nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time) |
| Smoother method - does the smoothing on a segment. More...
|
|
double | getFieldByDim (const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim) |
| Get the field value for a given dimension. More...
|
|
void | setFieldByDim (geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value) |
| Set the field value for a given dimension. More...
|
|
|
double | tolerance_ |
|
double | data_w_ |
|
double | smooth_w_ |
|
int | max_its_ |
|
int | refinement_ctr_ |
|
int | refinement_num_ |
|
bool | do_refinement_ |
|
bool | enforce_path_inversion_ |
|
std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > | costmap_sub_ |
|
rclcpp::Logger | logger_ {rclcpp::get_logger("SimpleSmoother")} |
|
A path smoother implementation.
Definition at line 43 of file simple_smoother.hpp.
◆ getFieldByDim()
double nav2_smoother::SimpleSmoother::getFieldByDim |
( |
const geometry_msgs::msg::PoseStamped & |
msg, |
|
|
const unsigned int & |
dim |
|
) |
| |
|
inlineprotected |
Get the field value for a given dimension.
- Parameters
-
msg | Current pose to sample |
dim | Dimension ID of interest |
- Returns
- dim value
Definition at line 205 of file simple_smoother.cpp.
◆ setFieldByDim()
void nav2_smoother::SimpleSmoother::setFieldByDim |
( |
geometry_msgs::msg::PoseStamped & |
msg, |
|
|
const unsigned int |
dim, |
|
|
const double & |
value |
|
) |
| |
|
inlineprotected |
Set the field value for a given dimension.
- Parameters
-
msg | Current pose to sample |
dim | Dimension ID of interest |
value | to set the dimension to for the pose |
Definition at line 217 of file simple_smoother.cpp.
◆ smooth()
bool nav2_smoother::SimpleSmoother::smooth |
( |
nav_msgs::msg::Path & |
path, |
|
|
const rclcpp::Duration & |
max_time |
|
) |
| |
|
overridevirtual |
Method to smooth given path.
- Parameters
-
path | In-out path to be smoothed |
max_time | Maximum duration smoothing should take |
- Returns
- If smoothing was completed (true) or interrupted by time limit (false)
Implements nav2_core::Smoother.
Definition at line 62 of file simple_smoother.cpp.
◆ smoothImpl()
void nav2_smoother::SimpleSmoother::smoothImpl |
( |
nav_msgs::msg::Path & |
path, |
|
|
bool & |
reversing_segment, |
|
|
const nav2_costmap_2d::Costmap2D * |
costmap, |
|
|
const double & |
max_time |
|
) |
| |
|
protected |
The documentation for this class was generated from the following files: