22 #ifndef _GPURAYSENSOR_HH_
23 #define _GPURAYSENSOR_HH_
27 #include <boost/thread/mutex.hpp>
29 #include <ignition/math/Angle.hh>
30 #include <ignition/math/Pose3.hh>
65 public:
virtual void Load(
const std::string &_worldName,
66 sdf::ElementPtr _sdf);
70 public:
virtual void Load(
const std::string &_worldName);
73 public:
virtual void Init();
76 protected:
virtual bool UpdateImpl(
bool _force);
79 protected:
virtual void Fini();
82 public:
virtual std::string GetTopic()
const;
87 {
return this->laserCam;}
97 public: ignition::math::Angle AngleMin() const;
101 public:
void SetAngleMin(
double _angle);
111 public: ignition::math::Angle AngleMax() const;
115 public:
void SetAngleMax(
double _angle);
118 public:
double GetAngleResolution() const;
122 public:
double GetRangeMin() const;
126 public:
double GetRangeMax() const;
135 public:
double GetRangeResolution() const;
139 public:
int GetRayCount() const;
143 public:
int GetRangeCount() const;
147 public:
int GetVerticalRayCount() const;
151 public:
int GetVerticalRangeCount() const;
157 public: math::Angle GetVerticalAngleMin() const GAZEBO_DEPRECATED(6.0);
161 public: ignition::math::Angle VerticalAngleMin() const;
165 public:
void SetVerticalAngleMin(
double _angle);
171 public: math::Angle GetVerticalAngleMax() const GAZEBO_DEPRECATED(6.0);
175 public: ignition::math::Angle VerticalAngleMax() const;
179 public:
void SetVerticalAngleMax(
double _angle);
183 public:
double GetVerticalAngleResolution() const;
194 public:
double GetRange(
int _index);
198 public:
void GetRanges(std::vector<
double> &_ranges);
209 public:
double GetRetro(
int _index) const;
220 public:
int GetFiducial(
int _index) const;
224 public:
unsigned int GetCameraCount() const;
228 public:
bool IsHorizontal() const;
236 public:
double GetRayCountRatio() const;
244 public:
double GetRangeCountRatio() const;
248 public:
double GetHorzFOV() const;
252 public:
double GetCosHorzFOV() const;
255 public:
double GetVertFOV() const;
259 public:
double GetCosVertFOV() const;
263 public:
double GetHorzHalfAngle() const;
267 public:
double GetVertHalfAngle() const;
272 boost::function<
void(const
float *,
unsigned int,
unsigned int,
273 unsigned int, const std::
string &)> _subscriber);
277 public:
void DisconnectNewLaserFrame(event::
ConnectionPtr &_conn);
280 public: virtual
bool IsActive();
283 private:
void Render();
286 protected: sdf::ElementPtr scanElem;
289 protected: sdf::ElementPtr horzElem;
292 protected: sdf::ElementPtr vertElem;
295 protected: sdf::ElementPtr rangeElem;
298 protected: sdf::ElementPtr cameraElem;
301 protected:
unsigned int horzRayCount;
304 protected:
unsigned int vertRayCount;
307 protected:
unsigned int horzRangeCount;
310 protected:
unsigned int vertRangeCount;
313 protected:
double rangeCountRatio;
319 private: boost::mutex mutex;
322 private: msgs::LaserScanStamped laserMsg;
325 private: physics::
EntityPtr parentEntity;
331 private:
bool rendered;
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:147
GPU based laser sensor.
Definition: GpuRaySensor.hh:54
Forward declarations for transport.
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:47
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:76
boost::shared_ptr< GpuLaser > GpuLaserPtr
Definition: RenderTypes.hh:99
rendering::GpuLaserPtr GetLaserCamera() const
Returns a pointer to the internally kept rendering::GpuLaser.
Definition: GpuRaySensor.hh:86
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
An angle and related functions.
Definition: Angle.hh:53
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
Base class for sensors.
Definition: Sensor.hh:69
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:66