Public Member Functions | Protected Attributes | List of all members
global_planner::OrientationFilter Class Reference

#include <orientation_filter.h>

Public Member Functions

void interpolate (std::vector< geometry_msgs::PoseStamped > &path, int start_index, int end_index)
 
 OrientationFilter ()
 
virtual void processPath (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &path)
 
void setAngleBasedOnPositionDerivative (std::vector< geometry_msgs::PoseStamped > &path, int index)
 
void setMode (OrientationMode new_mode)
 
void setMode (int new_mode)
 
void setWindowSize (size_t window_size)
 

Protected Attributes

OrientationMode omode_
 
int window_size_
 

Detailed Description

Definition at line 45 of file orientation_filter.h.

Constructor & Destructor Documentation

global_planner::OrientationFilter::OrientationFilter ( )
inline

Definition at line 47 of file orientation_filter.h.

Member Function Documentation

void global_planner::OrientationFilter::interpolate ( std::vector< geometry_msgs::PoseStamped > &  path,
int  start_index,
int  end_index 
)

Definition at line 122 of file orientation_filter.cpp.

void global_planner::OrientationFilter::processPath ( const geometry_msgs::PoseStamped &  start,
std::vector< geometry_msgs::PoseStamped > &  path 
)
virtual

Definition at line 53 of file orientation_filter.cpp.

void global_planner::OrientationFilter::setAngleBasedOnPositionDerivative ( std::vector< geometry_msgs::PoseStamped > &  path,
int  index 
)

Definition at line 108 of file orientation_filter.cpp.

void global_planner::OrientationFilter::setMode ( OrientationMode  new_mode)
inline

Definition at line 57 of file orientation_filter.h.

void global_planner::OrientationFilter::setMode ( int  new_mode)
inline

Definition at line 58 of file orientation_filter.h.

void global_planner::OrientationFilter::setWindowSize ( size_t  window_size)
inline

Definition at line 60 of file orientation_filter.h.

Member Data Documentation

OrientationMode global_planner::OrientationFilter::omode_
protected

Definition at line 62 of file orientation_filter.h.

int global_planner::OrientationFilter::window_size_
protected

Definition at line 63 of file orientation_filter.h.


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


global_planner
Author(s): David Lu!!
autogenerated on Thu Jan 21 2021 04:06:07