Public Types | Public Member Functions | List of all members
vigir_footstep_planning::TerrainModelPlugin Class Referenceabstract

#include <terrain_model_plugin.h>

Inheritance diagram for vigir_footstep_planning::TerrainModelPlugin:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< const TerrainModelPluginConstPtr
 
typedef boost::shared_ptr< TerrainModelPluginPtr
 
- Public Types inherited from vigir_footstep_planning::CollisionCheckPlugin
enum  { FOOT = 1, UPPER_BODY = 2, FOOT_CONTACT_SUPPORT = 4 }
 
typedef boost::shared_ptr< const CollisionCheckPluginConstPtr
 
typedef boost::shared_ptr< CollisionCheckPluginPtr
 

Public Member Functions

virtual bool getFootContactSupport (const geometry_msgs::Pose &p, double &support, pcl::PointCloud< pcl::PointXYZI >::Ptr checked_positions=pcl::PointCloud< pcl::PointXYZI >::Ptr()) const
 
virtual bool getHeight (double x, double y, double &height) const
 
virtual bool getPointWithNormal (const pcl::PointNormal &p_search, pcl::PointNormal &p_result) const
 
virtual double getResolution () const =0
 
virtual bool isTerrainModelAvailable () const =0
 
bool isUnique () const final
 
 TerrainModelPlugin (const std::string &name)
 
virtual bool update3DData (geometry_msgs::Pose &p) const =0
 
virtual bool update3DData (State &s) const =0
 
- Public Member Functions inherited from vigir_footstep_planning::CollisionCheckPlugin
 CollisionCheckPlugin (const std::string &name)
 
bool initialize (const vigir_generic_params::ParameterSet &params=vigir_generic_params::ParameterSet()) override
 
virtual bool isAccessible (const State &s) const =0
 
virtual bool isAccessible (const State &next, const State &current) const =0
 
virtual bool isCollisionCheckAvailable () const
 
bool isUnique () const override
 
bool loadParams (const vigir_generic_params::ParameterSet &params=vigir_generic_params::ParameterSet()) override
 
virtual void reset ()
 Resets the plugin to initial state. More...
 

Detailed Description

Definition at line 45 of file terrain_model_plugin.h.

Member Typedef Documentation

Definition at line 51 of file terrain_model_plugin.h.

Definition at line 50 of file terrain_model_plugin.h.

Constructor & Destructor Documentation

vigir_footstep_planning::TerrainModelPlugin::TerrainModelPlugin ( const std::string &  name)

Definition at line 7 of file terrain_model_plugin.cpp.

Member Function Documentation

bool vigir_footstep_planning::TerrainModelPlugin::getFootContactSupport ( const geometry_msgs::Pose p,
double &  support,
pcl::PointCloud< pcl::PointXYZI >::Ptr  checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr() 
) const
virtual

Definition at line 27 of file terrain_model_plugin.cpp.

bool vigir_footstep_planning::TerrainModelPlugin::getHeight ( double  x,
double  y,
double &  height 
) const
virtual

Definition at line 22 of file terrain_model_plugin.cpp.

bool vigir_footstep_planning::TerrainModelPlugin::getPointWithNormal ( const pcl::PointNormal &  p_search,
pcl::PointNormal &  p_result 
) const
virtual

Definition at line 17 of file terrain_model_plugin.cpp.

virtual double vigir_footstep_planning::TerrainModelPlugin::getResolution ( ) const
pure virtual
virtual bool vigir_footstep_planning::TerrainModelPlugin::isTerrainModelAvailable ( ) const
pure virtual
bool vigir_footstep_planning::TerrainModelPlugin::isUnique ( ) const
final

Definition at line 12 of file terrain_model_plugin.cpp.

virtual bool vigir_footstep_planning::TerrainModelPlugin::update3DData ( geometry_msgs::Pose p) const
pure virtual
virtual bool vigir_footstep_planning::TerrainModelPlugin::update3DData ( State s) const
pure virtual

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


vigir_footstep_planning_plugins
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:47:39