Public Member Functions | Private Attributes | List of all members
industrial_trajectory_filters::NPointFilter< T > Class Template Reference

This is a simple filter which reduces a trajectory to N points or less. More...

#include <n_point_filter.h>

Inheritance diagram for industrial_trajectory_filters::NPointFilter< T >:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure ()
 FilterBase method for the sub class to configure the filter This function must be implemented in the derived class. More...
 
 NPointFilter ()
 Default constructor. More...
 
bool update (const T &trajectory_in, T &trajectory_out)
 Reduces a trajectory to N points or less. The resulting trajectory contains only point within the original trajectory (no interpolation is done between points). More...
 
 ~NPointFilter ()
 Default destructor. More...
 
- Public Member Functions inherited from industrial_trajectory_filters::FilterBase< T >
 FilterBase ()
 Default constructor. More...
 
const std::string & getName ()
 Original FitlerBase Method. More...
 
std::string getType ()
 Original FilterBase method, return filter type. More...
 
virtual ~FilterBase ()
 
- Public Member Functions inherited from planning_request_adapter::PlanningRequestAdapter
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 ()
 

Private Attributes

int n_points_
 number of points to reduce trajectory to More...
 

Additional Inherited Members

- Public Types inherited from planning_request_adapter::PlanningRequestAdapter
typedef boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
 
- Protected Member Functions inherited from industrial_trajectory_filters::FilterBase< T >
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
 Moveit Planning Request Adapter method. This basic implementation of the adaptAndPlan method calls the planner and then maps the trajectory data from the MotionPlanResponse object into the MessageAdapter mapping structure. The MessageAdapter object is then passed to the "update" method that resembles that from the old FilterBase interface class. The filtered trajectory is finally saved in the MotionPlanResponse object. More...
 
virtual std::string getDescription () const
 Return description string. More...
 
- Protected Attributes inherited from industrial_trajectory_filters::FilterBase< T >
bool configured_
 Holds filter configuration state. More...
 
std::string filter_name_
 filter name More...
 
std::string filter_type_
 
ros::NodeHandle nh_
 Internal node handle (used for parameter lookup) More...
 

Detailed Description

template<typename T>
class industrial_trajectory_filters::NPointFilter< T >

This is a simple filter which reduces a trajectory to N points or less.

Definition at line 45 of file n_point_filter.h.

Constructor & Destructor Documentation

template<typename T >
NPointFilter::NPointFilter ( )

Default constructor.

Definition at line 41 of file n_point_filter.cpp.

template<typename T >
NPointFilter::~NPointFilter ( )

Default destructor.

Definition at line 51 of file n_point_filter.cpp.

Member Function Documentation

template<typename T >
bool NPointFilter::configure ( )
virtual

FilterBase method for the sub class to configure the filter This function must be implemented in the derived class.

Returns
true if successful, otherwise false.

Implements industrial_trajectory_filters::FilterBase< T >.

Definition at line 56 of file n_point_filter.cpp.

template<typename T >
bool NPointFilter::update ( const T &  trajectory_in,
T &  trajectory_out 
)
virtual

Reduces a trajectory to N points or less. The resulting trajectory contains only point within the original trajectory (no interpolation is done between points).

Parameters
trajectory_ininput trajectory
trajectory_outfiltered trajectory (N points or less
Returns
true if successful

Implements industrial_trajectory_filters::FilterBase< T >.

Definition at line 74 of file n_point_filter.cpp.

Member Data Documentation

template<typename T >
int industrial_trajectory_filters::NPointFilter< T >::n_points_
private

number of points to reduce trajectory to

Definition at line 78 of file n_point_filter.h.


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


open_manipulator_moveit
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:12:12