acoustic_pinger_plugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef VRX_GAZEBO_ACOUSTIC_PINGER_PLUGIN_HH_
19 #define VRX_GAZEBO_ACOUSTIC_PINGER_PLUGIN_HH_
20 
21 #include <geometry_msgs/Vector3.h>
22 #include <ros/ros.h>
23 #include <memory>
24 #include <mutex>
25 #include <string>
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>
32 
33 namespace gazebo
34 {
56 class AcousticPinger : public ModelPlugin
57 {
59  public: AcousticPinger();
60 
62  public: virtual ~AcousticPinger();
63 
64  // Documentation inherited.
65  public: void Load(physics::ModelPtr _parent,
66  sdf::ElementPtr _sdf);
67 
69  protected: virtual void Update();
70 
74  public: void PingerPositionCallback(
75  const geometry_msgs::Vector3ConstPtr &_pos);
76 
77  // ROS integration
79  private: std::unique_ptr<ros::NodeHandle> rosNodeHandle;
80 
83 
86 
88  public: std::mutex mutex;
89 
91  private: physics::ModelPtr model;
92 
94  private: ignition::math::Vector3d position;
95 
96  // Variables that contain parameters of sensor simulation.
98  private: std::string frameId;
99 
101  private: float updateRate;
102 
105  private: common::Time lastUpdateTime;
106 
108  private: event::ConnectionPtr updateConnection;
109 
110  // From Brian Bingham's rangebearing_gazebo_plugin.
112  private: gazebo::sensors::NoisePtr rangeNoise = nullptr;
113 
115  private: gazebo::sensors::NoisePtr bearingNoise = nullptr;
116 
118  private: gazebo::sensors::NoisePtr elevationNoise = nullptr;
119 };
120 }
121 
122 #endif
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.
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...


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:46