#include <terrain_model_plugin.h>

Public Types | |
| typedef boost::shared_ptr< const TerrainModelPlugin > | ConstPtr |
| typedef boost::shared_ptr< TerrainModelPlugin > | Ptr |
Public Types inherited from vigir_footstep_planning::CollisionCheckPlugin | |
| enum | { FOOT = 1, UPPER_BODY = 2, FOOT_CONTACT_SUPPORT = 4 } |
| typedef boost::shared_ptr< const CollisionCheckPlugin > | ConstPtr |
| typedef boost::shared_ptr< CollisionCheckPlugin > | Ptr |
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 ¶ms=vigir_generic_params::ParameterSet()) override |
| virtual bool | isAccessible (const State &s) const =0 |
| virtual bool | isAccessible (const State &next, const State ¤t) const =0 |
| virtual bool | isCollisionCheckAvailable () const |
| bool | isUnique () const override |
| bool | loadParams (const vigir_generic_params::ParameterSet ¶ms=vigir_generic_params::ParameterSet()) override |
| virtual void | reset () |
| Resets the plugin to initial state. More... | |
Definition at line 45 of file terrain_model_plugin.h.
| typedef boost::shared_ptr<const TerrainModelPlugin> vigir_footstep_planning::TerrainModelPlugin::ConstPtr |
Definition at line 51 of file terrain_model_plugin.h.
Definition at line 50 of file terrain_model_plugin.h.
| vigir_footstep_planning::TerrainModelPlugin::TerrainModelPlugin | ( | const std::string & | name | ) |
Definition at line 7 of file terrain_model_plugin.cpp.
|
virtual |
Definition at line 27 of file terrain_model_plugin.cpp.
|
virtual |
Definition at line 22 of file terrain_model_plugin.cpp.
|
virtual |
Definition at line 17 of file terrain_model_plugin.cpp.
|
pure virtual |
|
pure virtual |
|
final |
Definition at line 12 of file terrain_model_plugin.cpp.
|
pure virtual |
|
pure virtual |