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

This is a simple filter which performs a uniforming sampling of a trajectory using linear interpolation. More...

#include <uniform_sample_filter.h>

Inheritance diagram for industrial_trajectory_filters::UniformSampleFilter< 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...
 
bool interpolatePt (trajectory_msgs::JointTrajectoryPoint &p1, trajectory_msgs::JointTrajectoryPoint &p2, double time_from_start, trajectory_msgs::JointTrajectoryPoint &interp_pt)
 Perform interpolation between p1 and p2. Time from start must be in between p1 and p2 times. More...
 
 UniformSampleFilter ()
 Default constructor. More...
 
bool update (const T &trajectory_in, T &trajectory_out)
 
 ~UniformSampleFilter ()
 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

double sample_duration_
 uniform sample duration (sec) 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::UniformSampleFilter< T >

This is a simple filter which performs a uniforming sampling of a trajectory using linear interpolation.

Definition at line 55 of file uniform_sample_filter.h.

Constructor & Destructor Documentation

template<typename T >
UniformSampleFilter::UniformSampleFilter ( )

Default constructor.

Definition at line 41 of file uniform_sample_filter.cpp.

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

Default destructor.

Definition at line 51 of file uniform_sample_filter.cpp.

Member Function Documentation

template<typename T >
bool UniformSampleFilter::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 uniform_sample_filter.cpp.

template<typename T >
bool UniformSampleFilter::interpolatePt ( trajectory_msgs::JointTrajectoryPoint &  p1,
trajectory_msgs::JointTrajectoryPoint &  p2,
double  time_from_start,
trajectory_msgs::JointTrajectoryPoint &  interp_pt 
)

Perform interpolation between p1 and p2. Time from start must be in between p1 and p2 times.

Parameters
p1prior trajectory point
p2subsequent trajectory point
time_from_starttime from start of trajectory (i.e. p0).
interp_ptresulting interpolated point
Returns
true if successful, otherwise false.

Definition at line 129 of file uniform_sample_filter.cpp.

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

Uniformly samples(in terms of time) the input trajectory based upon the sample duration. Sampling is performed via interpolation ensuring smooth velocity and acceleration. NOTE: For this reason trajectories must be fully defined before using this filter.

Parameters
trajectory_innon uniform trajectory
trajectory_outuniform(in terms of time) trajectory
Returns

Implements industrial_trajectory_filters::FilterBase< T >.

Definition at line 68 of file uniform_sample_filter.cpp.

Member Data Documentation

template<typename T >
double industrial_trajectory_filters::UniformSampleFilter< T >::sample_duration_
private

uniform sample duration (sec)

Definition at line 96 of file uniform_sample_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