18 #ifndef VRX_GAZEBO_ACOUSTIC_PINGER_PLUGIN_HH_ 19 #define VRX_GAZEBO_ACOUSTIC_PINGER_PLUGIN_HH_ 21 #include <geometry_msgs/Vector3.h> 26 #include <gazebo/common/Events.hh> 27 #include <gazebo/common/Plugin.hh> 28 #include <gazebo/common/Time.hh> 29 #include <gazebo/physics/physics.hh> 30 #include <gazebo/sensors/GaussianNoiseModel.hh> 31 #include <ignition/math/Vector3.hh> 65 public:
void Load(physics::ModelPtr _parent,
66 sdf::ElementPtr _sdf);
69 protected:
virtual void Update();
75 const geometry_msgs::Vector3ConstPtr &_pos);
91 private: physics::ModelPtr
model;
physics::ModelPtr model
Pointer to model object.
ros::Subscriber setPositionSub
Subscribes to the topic that set the pinger position.
float updateRate
Sensor update rate.
event::ConnectionPtr updateConnection
Pointer used to connect gazebo callback to plugins update function.
virtual void Update()
Callback used by gazebo to update the plugin.
AcousticPinger()
Constructor.
gazebo::sensors::NoisePtr rangeNoise
rangeNoise - Gazebo noise object for range.
gazebo::sensors::NoisePtr elevationNoise
Gazebo noise object for elevation angle.
std::mutex mutex
Mutex to protect the position vector.
common::Time lastUpdateTime
Variable used to track time of last update. This is used to produce data at the correct rate...
virtual ~AcousticPinger()
Destructor.
Implements a simulated range and bearing pinger localisation system.
ros::Publisher rangeBearingPub
Publisher used to send sensor messages generated by the plugin.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::string frameId
String holding the frame id of the sensor.
ignition::math::Vector3d position
Vector storing the position of the pinger.
std::unique_ptr< ros::NodeHandle > rosNodeHandle
Nodehandle used to integrate with the ROS system.
gazebo::sensors::NoisePtr bearingNoise
Gazebo noise object for bearing angle.
void PingerPositionCallback(const geometry_msgs::Vector3ConstPtr &_pos)
Callback function called when receiving a new pinger position via the pinger subscription callback...