17 #ifndef GAZEBO_PHYSICS_HEIGHTMAPSHAPE_HH_ 18 #define GAZEBO_PHYSICS_HEIGHTMAPSHAPE_HH_ 22 #include <ignition/transport/Node.hh> 24 #include <ignition/math/Vector2.hh> 59 public:
virtual void Load(sdf::ElementPtr _sdf);
62 public:
virtual void Init();
66 public:
virtual void SetScale(
const ignition::math::Vector3d &_scale);
70 public: std::string GetURI()
const;
74 public: ignition::math::Vector3d Size()
const;
78 public: ignition::math::Vector3d Pos()
const;
84 public: ignition::math::Vector2i VertexCount()
const;
90 public: HeightType GetHeight(
int _x,
int _y)
const;
96 public:
void FillMsg(msgs::Geometry &_msg);
100 public:
void FillHeights(msgs::Geometry &_msg)
const;
104 public:
virtual void ProcessMsg(
const msgs::Geometry &_msg);
107 public:
virtual double ComputeVolume()
const;
111 public: HeightType GetMaxHeight()
const;
115 public: HeightType GetMinHeight()
const;
119 public:
int GetSubSampling()
const;
132 private:
int LoadTerrainFile(
const std::string &_filename);
136 private:
void OnRequest(ConstRequestPtr &_msg);
141 public:
void FillHeightfield(std::vector<float>& heights);
144 public:
void FillHeightfield(std::vector<double>& heights);
174 private: std::string fileFormat;
177 private: ignition::math::Vector3d heightmapSize;
188 private: ignition::transport::Node nodeIgn;
191 private: ignition::transport::Node::Publisher responsePubIgn;
Forward declarations for the common classes.
Definition: Animation.hh:26
HeightmapShape collision shape builds a heightmap from an image.
Definition: HeightmapShape.hh:45
Encapsulates a generic heightmap data file.
Definition: HeightmapData.hh:39
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
Base class for all shapes.
Definition: Shape.hh:45
Encapsulates an image that will be interpreted as a heightmap.
Definition: ImageHeightmap.hh:38
float HeightType
height field type, float or double
Definition: HeightmapShape.hh:48
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
default namespace for gazebo
unsigned int vertSize
Size of the height lookup table.
Definition: HeightmapShape.hh:156
int subSampling
The amount of subsampling. Default is 2.
Definition: HeightmapShape.hh:162
bool flipY
True to flip the heights along the y direction.
Definition: HeightmapShape.hh:159
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
common::ImageHeightmap img
Image used to generate the heights.
Definition: HeightmapShape.hh:150
Encapsulates an image.
Definition: Image.hh:74
common::HeightmapData * heightmapData
HeightmapData used to generate the heights.
Definition: HeightmapShape.hh:153
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113
std::vector< HeightType > heights
Lookup table of heights.
Definition: HeightmapShape.hh:147