gazebo_ros_magnetic.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
30 #include <gazebo/common/Events.hh>
31 #include <gazebo/physics/physics.hh>
32 
33 static const double DEFAULT_MAGNITUDE = 1.0;
34 static const double DEFAULT_REFERENCE_HEADING = 0.0;
35 static const double DEFAULT_DECLINATION = 0.0;
36 static const double DEFAULT_INCLINATION = 60.0;
37 
38 namespace gazebo {
39 
41 {
42 }
43 
45 // Destructor
47 {
49 
51 
53  delete node_handle_;
54 }
55 
57 // Load the controller
58 void GazeboRosMagnetic::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
59 {
60  world = _model->GetWorld();
61 
62  // load parameters
63  if (_sdf->HasElement("robotNamespace"))
64  namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
65  else
66  namespace_.clear();
67 
68  if (!_sdf->HasElement("topicName"))
69  topic_ = "magnetic";
70  else
71  topic_ = _sdf->GetElement("topicName")->Get<std::string>();
72 
73 
74  if (_sdf->HasElement("bodyName"))
75  {
76  link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
77  link = _model->GetLink(link_name_);
78  }
79  else
80  {
81  link = _model->GetLink();
82  link_name_ = link->GetName();
83  }
84 
85  if (!link)
86  {
87  ROS_FATAL("GazeboRosMagnetic plugin error: bodyName: %s does not exist\n", link_name_.c_str());
88  return;
89  }
90 
91  // default parameters
95  declination_ = DEFAULT_DECLINATION * M_PI/180.0;
96  inclination_ = DEFAULT_INCLINATION * M_PI/180.0;
97 
98  if (_sdf->HasElement("frameId"))
99  frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
100 
101  if (_sdf->HasElement("magnitude"))
102  _sdf->GetElement("magnitude")->GetValue()->Get(magnitude_);
103 
104  if (_sdf->HasElement("referenceHeading"))
105  if (_sdf->GetElement("referenceHeading")->GetValue()->Get(reference_heading_))
106  reference_heading_ *= M_PI/180.0;
107 
108  if (_sdf->HasElement("declination"))
109  if (_sdf->GetElement("declination")->GetValue()->Get(declination_))
110  declination_ *= M_PI/180.0;
111 
112  if (_sdf->HasElement("inclination"))
113  if (_sdf->GetElement("inclination")->GetValue()->Get(inclination_))
114  inclination_ *= M_PI/180.0;
115 
116  if (_sdf->HasElement("useMagneticFieldMsgs"))
117  _sdf->GetElement("useMagneticFieldMsgs")->GetValue()->Get(use_magnetic_field_msgs_);
118  else
119  use_magnetic_field_msgs_ = false;
120 
121  // Note: Gazebo uses NorthWestUp coordinate system, heading and declination are compass headings
122 #if (GAZEBO_MAJOR_VERSION >= 8)
126 #else
130 #endif
131 
132  sensor_model_.Load(_sdf);
133 
134  // start ros node
135  if (!ros::isInitialized())
136  {
137  int argc = 0;
138  char** argv = NULL;
140  }
141 
144  publisher_ = node_handle_->advertise<sensor_msgs::MagneticField>(topic_, 1);
145  else
146  publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(topic_, 1);
147 
148  // setup dynamic_reconfigure server
149  dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_)));
151 
152  Reset();
153 
154  // connect Update function
155  updateTimer.Load(world, _sdf);
157 }
158 
160 {
161  updateTimer.Reset();
163 }
164 
166 // Update the controller
168 {
169 #if (GAZEBO_MAJOR_VERSION >= 8)
170  common::Time sim_time = world->SimTime();
171  double dt = updateTimer.getTimeSinceLastUpdate().Double();
172  ignition::math::Pose3d pose = link->WorldPose();
173  ignition::math::Vector3d field = sensor_model_(pose.Rot().RotateVectorReverse(magnetic_field_world_), dt);
174 #else
175  common::Time sim_time = world->GetSimTime();
176  double dt = updateTimer.getTimeSinceLastUpdate().Double();
177 
178  math::Pose pose = link->GetWorldPose();
179  math::Vector3 field = sensor_model_(pose.rot.RotateVectorReverse(magnetic_field_world_), dt);
180 #endif
181 
183  {
184  sensor_msgs::MagneticField magnetic_field;
185 
186  magnetic_field.header.stamp = ros::Time(sim_time.sec, sim_time.nsec);
187  magnetic_field.header.frame_id = frame_id_;
188 #if (GAZEBO_MAJOR_VERSION >= 8)
189  magnetic_field.magnetic_field.x = field.X();
190  magnetic_field.magnetic_field.y = field.Y();
191  magnetic_field.magnetic_field.z = field.Z();
192 #else
193  magnetic_field.magnetic_field.x = field.x;
194  magnetic_field.magnetic_field.y = field.y;
195  magnetic_field.magnetic_field.z = field.z;
196 #endif
197 
198  // future work: implement support for the magnetic_field_covariance
199  // e.g. magnetic_field_new_.magnetic_field_covariance = [...]
200  // by leaving it alone it'll be all-zeros, indicating "unknown" which is fine
201 
202  publisher_.publish(magnetic_field);
203  }
204  else
205  {
206  geometry_msgs::Vector3Stamped magnetic_field;
207 
208  magnetic_field.header.stamp = ros::Time(sim_time.sec, sim_time.nsec);
209  magnetic_field.header.frame_id = frame_id_;
210 #if (GAZEBO_MAJOR_VERSION >= 8)
211  magnetic_field.vector.x = field.X();
212  magnetic_field.vector.y = field.Y();
213  magnetic_field.vector.z = field.Z();
214 #else
215  magnetic_field.vector.x = field.x;
216  magnetic_field.vector.y = field.y;
217  magnetic_field.vector.z = field.z;
218 #endif
219 
220  publisher_.publish(magnetic_field);
221  }
222 }
223 
224 // Register this plugin with the simulator
225 GZ_REGISTER_MODEL_PLUGIN(GazeboRosMagnetic)
226 
227 } // namespace gazebo
event::ConnectionPtr updateConnection
#define ROS_FATAL(...)
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string &_prefix="update")
Definition: update_timer.h:52
static const double DEFAULT_DECLINATION
void publish(const boost::shared_ptr< M > &message) const
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix=std::string())
Definition: sensor_model.h:101
physics::LinkPtr link
The link referred to by this plugin.
ROSCPP_DECL bool isInitialized()
virtual void Reset()
Definition: update_timer.h:175
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual event::ConnectionPtr Connect(const boost::function< void()> &_subscriber, bool connectToWorldUpdateBegin=true)
Definition: update_timer.h:85
static const double DEFAULT_MAGNITUDE
gazebo::math::Vector3 magnetic_field_world_
physics::WorldPtr world
The parent World.
virtual void Disconnect(event::ConnectionPtr const &_c=event::ConnectionPtr())
Definition: update_timer.h:95
virtual void dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level)
common::Time getTimeSinceLastUpdate() const
Definition: update_timer.h:132
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static const double DEFAULT_REFERENCE_HEADING
virtual void reset()
Definition: sensor_model.h:191
static const double DEFAULT_INCLINATION
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_
ros::NodeHandle * node_handle_


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Fri Feb 5 2021 03:48:30