Public Member Functions | |
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. | |
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. | |
virtual std::string | getDescription () const |
Returns a short description of this plugin. | |
~AddSmoothingFilter () | |
Destructor. | |
Static Public Attributes | |
static const std::string | FILTER_PARAMETER_NAME_ = "/move_group/smoothing_filter_name" |
Private Attributes | |
std::vector< double > | filter_coef_ |
std::string | filter_name_ |
ros::NodeHandle | nh_ |
industrial_trajectory_filters::SmoothingTrajectoryFilter | smoothing_filter_ |
Definition at line 47 of file add_smoothing_filter.cpp.
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 57 of file add_smoothing_filter.cpp.
Destructor.
Definition at line 91 of file add_smoothing_filter.cpp.
virtual bool industrial_trajectory_filters::AddSmoothingFilter::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 [inline, virtual] |
The work hourse of planning request adapters.
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 103 of file add_smoothing_filter.cpp.
virtual std::string industrial_trajectory_filters::AddSmoothingFilter::getDescription | ( | ) | const [inline, virtual] |
Returns a short description of this plugin.
Reimplemented from planning_request_adapter::PlanningRequestAdapter.
Definition at line 94 of file add_smoothing_filter.cpp.
std::vector<double> industrial_trajectory_filters::AddSmoothingFilter::filter_coef_ [private] |
Definition at line 132 of file add_smoothing_filter.cpp.
std::string industrial_trajectory_filters::AddSmoothingFilter::filter_name_ [private] |
Definition at line 131 of file add_smoothing_filter.cpp.
const std::string industrial_trajectory_filters::AddSmoothingFilter::FILTER_PARAMETER_NAME_ = "/move_group/smoothing_filter_name" [static] |
Definition at line 51 of file add_smoothing_filter.cpp.
Definition at line 125 of file add_smoothing_filter.cpp.
industrial_trajectory_filters::SmoothingTrajectoryFilter industrial_trajectory_filters::AddSmoothingFilter::smoothing_filter_ [private] |
Definition at line 130 of file add_smoothing_filter.cpp.