Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef VIGIR_FOOTSTEP_PLANNING_TERRAIN_MODEL_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_TERRAIN_MODEL_H__
00031
00032 #include <ros/ros.h>
00033
00034 #include <boost/thread/mutex.hpp>
00035
00036 #include <pcl/point_cloud.h>
00037
00038 #include <vigir_footstep_planning_lib/modeling/state.h>
00039
00040 #include <vigir_footstep_planning_plugins/plugins/terrain_model_plugin.h>
00041
00042 #include <vigir_terrain_classifier/terrain_model.h>
00043
00044
00045
00046 namespace vigir_footstep_planning
00047 {
00048 class TerrainModel
00049 : public TerrainModelPlugin
00050 {
00051 public:
00052 TerrainModel(const std::string& name = "terrain_model");
00053
00054 bool initialize(const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet()) override;
00055
00056 bool loadParams(const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet()) override;
00057
00058 void reset();
00059
00060 bool isAccessible(const State& s) const override;
00061 bool isAccessible(const State& next, const State& current) const override;
00062
00063 bool isTerrainModelAvailable() const override;
00064
00065 void setTerrainModel(const vigir_terrain_classifier::TerrainModelMsg::ConstPtr& terrain_model);
00066
00067 double getResolution() const override;
00068
00069 bool getPointWithNormal(const pcl::PointNormal& p_search, pcl::PointNormal& p_result) const override;
00070 bool getHeight(double x, double y, double& height) const override;
00071 bool getFootContactSupport(const geometry_msgs::Pose& p, double& support, pcl::PointCloud<pcl::PointXYZI>::Ptr checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr()) const override;
00072 bool getFootContactSupport(const tf::Pose& p, double& support, pcl::PointCloud<pcl::PointXYZI>::Ptr checked_positions = pcl::PointCloud<pcl::PointXYZI>::Ptr()) const;
00073
00074 bool update3DData(geometry_msgs::Pose& p) const override;
00075 bool update3DData(State& s) const override;
00076
00077
00078 typedef boost::shared_ptr<TerrainModel> Ptr;
00079 typedef boost::shared_ptr<TerrainModel> ConstPtr;
00080
00081 protected:
00082 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;
00083
00084
00085 ros::Subscriber terrain_model_sub;
00086
00087
00088 mutable boost::shared_mutex terrain_model_shared_mutex;
00089
00090 vigir_terrain_classifier::TerrainModel::Ptr terrain_model;
00091
00092
00093 unsigned int min_sampling_steps_x;
00094 unsigned int min_sampling_steps_y;
00095 unsigned int max_sampling_steps_x;
00096 unsigned int max_sampling_steps_y;
00097 double max_intrusion_z;
00098 double max_ground_clearance;
00099 double minimal_support;
00100
00101
00102 geometry_msgs::Vector3 foot_size;
00103 };
00104 }
00105
00106 #endif