17 #ifndef GAZEBO_PHYSICS_MULTIRAYSHAPE_HH_ 18 #define GAZEBO_PHYSICS_MULTIRAYSHAPE_HH_ 22 #include <ignition/math/Angle.hh> 62 public:
virtual void Init();
66 public:
virtual void SetScale(
const ignition::math::Vector3d &_scale);
71 public:
double GetRange(
unsigned int _index);
76 public:
double GetRetro(
unsigned int _index);
81 public:
int GetFiducial(
unsigned int _index);
85 public:
double GetMinRange()
const;
89 public:
double GetMaxRange()
const;
93 public:
double GetResRange()
const;
97 public:
int GetSampleCount()
const;
101 public:
double GetScanResolution()
const;
105 public: ignition::math::Angle MinAngle()
const;
109 public: ignition::math::Angle MaxAngle()
const;
113 public:
int GetVerticalSampleCount()
const;
117 public:
double GetVerticalScanResolution()
const;
121 public: ignition::math::Angle VerticalMinAngle()
const;
125 public: ignition::math::Angle VerticalMaxAngle()
const;
128 public:
void Update();
133 public:
void FillMsg(msgs::Geometry &_msg);
138 public:
virtual void ProcessMsg(
const msgs::Geometry &_msg);
141 public:
virtual double ComputeVolume()
const;
146 public:
template<
typename T>
148 {
return this->newLaserScans.Connect(_subscriber);}
154 public:
virtual void UpdateRays() = 0;
159 public:
virtual void AddRay(
const ignition::math::Vector3d &_start,
160 const ignition::math::Vector3d &_end);
168 public:
bool SetRay(
const unsigned int _rayIndex,
169 const ignition::math::Vector3d &_start,
170 const ignition::math::Vector3d &_end);
174 public:
unsigned int RayCount()
const;
180 public:
RayShapePtr Ray(
const unsigned int _rayIndex)
const;
183 protected: std::vector<RayShapePtr>
rays;
186 protected: ignition::math::Pose3d
offset;
207 private:
double minRange = 0;
210 private:
double maxRange = 1000;
sdf::ElementPtr scanElem
Scan SDF element pointer.
Definition: MultiRayShape.hh:192
Forward declarations for the common classes.
Definition: Animation.hh:26
Laser collision contains a set of ray-collisions, structured to simulate a laser range scanner...
Definition: MultiRayShape.hh:39
Base class for all shapes.
Definition: Shape.hh:45
boost::shared_ptr< PhysicsEngine > PhysicsEnginePtr
Definition: PhysicsTypes.hh:125
ignition::math::Pose3d offset
Pose offset of all the rays.
Definition: MultiRayShape.hh:186
sdf::ElementPtr rayElem
Ray SDF element pointer.
Definition: MultiRayShape.hh:189
sdf::ElementPtr horzElem
Horizontal SDF element pointer.
Definition: MultiRayShape.hh:195
sdf::ElementPtr rangeElem
Range SDF element pointer.
Definition: MultiRayShape.hh:201
std::vector< RayShapePtr > rays
Ray data.
Definition: MultiRayShape.hh:183
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
boost::shared_ptr< RayShape > RayShapePtr
Definition: PhysicsTypes.hh:145
event::ConnectionPtr ConnectNewLaserScans(T _subscriber)
Connect a to the new laser scan signal.
Definition: MultiRayShape.hh:147
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113
event::EventT< void()> newLaserScans
New laser scans event.
Definition: MultiRayShape.hh:204
sdf::ElementPtr vertElem
Vertical SDF element pointer.
Definition: MultiRayShape.hh:198