#include <terrain_model.h>
|
bool | getFootContactSupport (const geometry_msgs::Pose &p, double &support, pcl::PointCloud< pcl::PointXYZI >::Ptr checked_positions=pcl::PointCloud< pcl::PointXYZI >::Ptr()) const override |
|
bool | getFootContactSupport (const tf::Pose &p, double &support, pcl::PointCloud< pcl::PointXYZI >::Ptr checked_positions=pcl::PointCloud< pcl::PointXYZI >::Ptr()) const |
|
bool | getHeight (double x, double y, double &height) const override |
|
bool | getPointWithNormal (const pcl::PointNormal &p_search, pcl::PointNormal &p_result) const override |
|
double | getResolution () const override |
|
bool | initialize (const vigir_generic_params::ParameterSet ¶ms=vigir_generic_params::ParameterSet()) override |
|
bool | isAccessible (const State &s) const override |
|
bool | isAccessible (const State &next, const State ¤t) const override |
|
bool | isTerrainModelAvailable () const override |
|
bool | loadParams (const vigir_generic_params::ParameterSet ¶ms=vigir_generic_params::ParameterSet()) override |
|
void | reset () |
|
void | setTerrainModel (const vigir_terrain_classifier::TerrainModelMsg::ConstPtr &terrain_model) |
|
| TerrainModel (const std::string &name="terrain_model") |
|
bool | update3DData (geometry_msgs::Pose &p) const override |
|
bool | update3DData (State &s) const override |
|
|
bool | getFootContactSupport (const tf::Pose &p, double &support, unsigned int sampling_steps_x, unsigned int sampling_steps_y, pcl::PointCloud< pcl::PointXYZI >::Ptr checked_positions=pcl::PointCloud< pcl::PointXYZI >::Ptr()) const |
|
Definition at line 48 of file terrain_model.h.
vigir_footstep_planning::TerrainModel::TerrainModel |
( |
const std::string & |
name = "terrain_model" | ) |
|
bool vigir_footstep_planning::TerrainModel::getFootContactSupport |
( |
const geometry_msgs::Pose & |
p, |
|
|
double & |
support, |
|
|
pcl::PointCloud< pcl::PointXYZI >::Ptr |
checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr() |
|
) |
| const |
|
override |
bool vigir_footstep_planning::TerrainModel::getFootContactSupport |
( |
const tf::Pose & |
p, |
|
|
double & |
support, |
|
|
pcl::PointCloud< pcl::PointXYZI >::Ptr |
checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr() |
|
) |
| const |
bool vigir_footstep_planning::TerrainModel::getFootContactSupport |
( |
const tf::Pose & |
p, |
|
|
double & |
support, |
|
|
unsigned int |
sampling_steps_x, |
|
|
unsigned int |
sampling_steps_y, |
|
|
pcl::PointCloud< pcl::PointXYZI >::Ptr |
checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr() |
|
) |
| const |
|
protected |
TODO: find efficient solution to prevent inconsistency
@ TODO: refinement (center of pressure)
Definition at line 134 of file terrain_model.cpp.
bool vigir_footstep_planning::TerrainModel::getHeight |
( |
double |
x, |
|
|
double |
y, |
|
|
double & |
height |
|
) |
| const |
|
override |
bool vigir_footstep_planning::TerrainModel::getPointWithNormal |
( |
const pcl::PointNormal & |
p_search, |
|
|
pcl::PointNormal & |
p_result |
|
) |
| const |
|
override |
double vigir_footstep_planning::TerrainModel::getResolution |
( |
| ) |
const |
|
override |
bool vigir_footstep_planning::TerrainModel::initialize |
( |
const vigir_generic_params::ParameterSet & |
params = vigir_generic_params::ParameterSet() | ) |
|
|
override |
bool vigir_footstep_planning::TerrainModel::isAccessible |
( |
const State & |
s | ) |
const |
|
override |
bool vigir_footstep_planning::TerrainModel::isAccessible |
( |
const State & |
next, |
|
|
const State & |
current |
|
) |
| const |
|
override |
bool vigir_footstep_planning::TerrainModel::isTerrainModelAvailable |
( |
| ) |
const |
|
override |
bool vigir_footstep_planning::TerrainModel::loadParams |
( |
const vigir_generic_params::ParameterSet & |
params = vigir_generic_params::ParameterSet() | ) |
|
|
override |
void vigir_footstep_planning::TerrainModel::reset |
( |
| ) |
|
void vigir_footstep_planning::TerrainModel::setTerrainModel |
( |
const vigir_terrain_classifier::TerrainModelMsg::ConstPtr & |
terrain_model | ) |
|
bool vigir_footstep_planning::TerrainModel::update3DData |
( |
geometry_msgs::Pose & |
p | ) |
const |
|
override |
bool vigir_footstep_planning::TerrainModel::update3DData |
( |
State & |
s | ) |
const |
|
override |
TODO: find efficient solution to prevent inconsistency
Definition at line 215 of file terrain_model.cpp.
geometry_msgs::Vector3 vigir_footstep_planning::TerrainModel::foot_size |
|
protected |
double vigir_footstep_planning::TerrainModel::max_ground_clearance |
|
protected |
double vigir_footstep_planning::TerrainModel::max_intrusion_z |
|
protected |
unsigned int vigir_footstep_planning::TerrainModel::max_sampling_steps_x |
|
protected |
unsigned int vigir_footstep_planning::TerrainModel::max_sampling_steps_y |
|
protected |
unsigned int vigir_footstep_planning::TerrainModel::min_sampling_steps_x |
|
protected |
unsigned int vigir_footstep_planning::TerrainModel::min_sampling_steps_y |
|
protected |
double vigir_footstep_planning::TerrainModel::minimal_support |
|
protected |
vigir_terrain_classifier::TerrainModel::Ptr vigir_footstep_planning::TerrainModel::terrain_model |
|
protected |
boost::shared_mutex vigir_footstep_planning::TerrainModel::terrain_model_shared_mutex |
|
mutableprotected |
The documentation for this class was generated from the following files: