MagnetometerROSPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
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 // This source code is derived from hector_gazebo
17 // (https://github.com/tu-darmstadt-ros-pkg/hector_gazebo)
18 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt,
19 // licensed under the BSD 3-Clause license,
20 // cf. 3rd-party-licenses.txt file in the root directory of this source tree.
21 //
22 // The original code was modified to:
23 // - be more consistent with other sensor plugins within uuv_simulator,
24 // - adhere to Gazebo's coding standards.
25 
26 #ifndef __UUV_MAGNETOMETER_ROS_PLUGIN_HH__
27 #define __UUV_MAGNETOMETER_ROS_PLUGIN_HH__
28 
29 #include "SensorMagnetic.pb.h"
30 #include <gazebo/gazebo.hh>
31 #include <ros/ros.h>
33 #include <sensor_msgs/MagneticField.h>
34 
35 namespace gazebo
36 {
38  {
40  double intensity;
42  double heading;
44  double declination;
46  double inclination;
48  double noiseXY;
50  double noiseZ;
53  double turnOnBias;
54  };
55 
57  {
59  public: MagnetometerROSPlugin();
60 
62  public: virtual ~MagnetometerROSPlugin();
63 
65  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
66 
68  protected: virtual bool OnUpdate(const common::UpdateInfo& _info);
69 
72 
74  protected: ignition::math::Vector3d magneticFieldWorld;
75 
77  protected: ignition::math::Vector3d turnOnBias;
78 
80  protected: ignition::math::Vector3d measMagneticField;
81 
83  protected: sensor_msgs::MagneticField rosMsg;
84  };
85 }
86 
87 #endif // __UUV_MAGNETOMETER_ROS_PLUGIN_HH__
MagnetometerParameters parameters
Magnetometer configuration parameters:
ignition::math::Vector3d measMagneticField
Last measurement of magnetic field.
double declination
Declination of reference earth magnetic field [rad].
double heading
Heading angle of reference earth magnetic field [rad].
double intensity
Intensity of reference earth magnetic field [muT].
ignition::math::Vector3d turnOnBias
Constant turn-on bias [muT].
sensor_msgs::MagneticField rosMsg
ROS message.
double noiseZ
Discrete-time standard dev. of output noise in z-axis [muT].
ignition::math::Vector3d magneticFieldWorld
Reference magnetic field in world frame:
double inclination
Inclination of reference earth magnetic field [rad].
double turnOnBias
Standard deviation of constant systematic offset of measurements [muT].
double noiseXY
Discrete-time standard dev. of output noise in xy-axis [muT].


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:33