|
virtual bool | adaptAndPlan (const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const |
| The work hourse of planning request adapters. More...
|
|
| AddSmoothingFilter () |
| Constructor AddSmoothingFilter is a planning request adapter plugin which post-processes The robot's trajectory to round out corners The filter name and then its coefficients are obtained from the ROS parameter server. More...
|
|
virtual std::string | getDescription () const |
| Returns a short description of this plugin. More...
|
|
virtual void | initialize (const ros::NodeHandle &node_handle) |
| load parameters from a certain namespace More...
|
|
| ~AddSmoothingFilter () |
| Destructor. More...
|
|
bool | adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const |
|
bool | adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const |
|
| PlanningRequestAdapter () |
|
virtual | ~PlanningRequestAdapter () |
|
Definition at line 48 of file add_smoothing_filter.cpp.
◆ AddSmoothingFilter()
industrial_trajectory_filters::AddSmoothingFilter::AddSmoothingFilter |
( |
| ) |
|
|
inline |
Constructor AddSmoothingFilter is a planning request adapter plugin which post-processes The robot's trajectory to round out corners The filter name and then its coefficients are obtained from the ROS parameter server.
Definition at line 58 of file add_smoothing_filter.cpp.
◆ ~AddSmoothingFilter()
industrial_trajectory_filters::AddSmoothingFilter::~AddSmoothingFilter |
( |
| ) |
|
|
inline |
◆ adaptAndPlan()
The work hourse of planning request adapters.
- Parameters
-
planner | A function called somewhere within this subroutine |
planning_scene | an object describing the objects and kinematics |
req | the request, includes the starting config, the goal, constraints, etc |
res | the response, includes the robot trajectory and other info |
added_path_index,a | index of the points added by this adapter, which in this case will be empty |
Implements planning_request_adapter::PlanningRequestAdapter.
Definition at line 121 of file add_smoothing_filter.cpp.
◆ getDescription()
virtual std::string industrial_trajectory_filters::AddSmoothingFilter::getDescription |
( |
| ) |
const |
|
inlinevirtual |
◆ initialize()
virtual void industrial_trajectory_filters::AddSmoothingFilter::initialize |
( |
const ros::NodeHandle & |
node_handle | ) |
|
|
inlinevirtual |
◆ filter_coef_
std::vector<double> industrial_trajectory_filters::AddSmoothingFilter::filter_coef_ |
|
private |
◆ filter_name_
std::string industrial_trajectory_filters::AddSmoothingFilter::filter_name_ |
|
private |
◆ FILTER_PARAMETER_NAME_
const std::string industrial_trajectory_filters::AddSmoothingFilter::FILTER_PARAMETER_NAME_ = "/move_group/smoothing_filter_name" |
|
static |
◆ nh_
◆ smoothing_filter_
The documentation for this class was generated from the following file: