gazebo_quadrotor_aerodynamics.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012-2016, Institute of Flight Systems and Automatic Control,
3 // Technische Universität Darmstadt.
4 // All rights reserved.
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of hector_quadrotor nor the names of its contributors
14 // may be used to endorse or promote products derived from this software
15 // without 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 
31 
32 #include <gazebo/common/Events.hh>
33 #include <gazebo/physics/physics.hh>
34 
35 #include <geometry_msgs/WrenchStamped.h>
36 
37 #if (GAZEBO_MAJOR_VERSION >= 8)
38 namespace hector_quadrotor_model {
39 
40 template <typename Message, typename T> static inline void toVector(const Message& msg, ignition::math::Vector3<T>& vector)
41 {
42  vector.X() = msg.x;
43  vector.Y() = msg.y;
44  vector.Z() = msg.z;
45 }
46 
47 template <typename Message, typename T> static inline void fromVector(const ignition::math::Vector3<T>& vector, Message& msg)
48 {
49  msg.x = vector.X();
50  msg.y = vector.Y();
51  msg.z = vector.Z();
52 }
53 
54 template <typename Message, typename T> static inline void toQuaternion(const Message& msg, ignition::math::Quaternion<T>& quaternion)
55 {
56  quaternion.W() = msg.w;
57  quaternion.X() = msg.x;
58  quaternion.Y() = msg.y;
59  quaternion.Z() = msg.z;
60 }
61 
62 template <typename Message, typename T> static inline void fromQuaternion(const ignition::math::Quaternion<T>& quaternion, Message& msg)
63 {
64  msg.w = quaternion.W();
65  msg.x = quaternion.X();
66  msg.y = quaternion.Y();
67  msg.z = quaternion.Z();
68 }
69 
70 } // namespace hector_quadrotor_model
71 #endif
72 
73 namespace gazebo {
74 
75 using namespace common;
76 using namespace hector_quadrotor_model;
77 
78 GazeboQuadrotorAerodynamics::GazeboQuadrotorAerodynamics()
79  : node_handle_(0)
80 {
81 }
82 
84 {
85 #if (GAZEBO_MAJOR_VERSION < 8)
86  event::Events::DisconnectWorldUpdateBegin(updateConnection);
87 #endif
88  updateConnection.reset();
89 
90  if (node_handle_) {
92  if (callback_queue_thread_.joinable())
94  delete node_handle_;
95  }
96 }
97 
99 // Load the controller
100 void GazeboQuadrotorAerodynamics::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
101 {
102  world = _model->GetWorld();
103  link = _model->GetLink();
104 
105  // default parameters
106  namespace_.clear();
107  param_namespace_ = "quadrotor_aerodynamics";
108  wind_topic_ = "/wind";
109  wrench_topic_ = "aerodynamics/wrench";
110  frame_id_ = link->GetName();
111 
112  // load parameters
113  if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>();
114  if (_sdf->HasElement("paramNamespace")) param_namespace_ = _sdf->GetElement("paramNamespace")->Get<std::string>();
115  if (_sdf->HasElement("windTopicName")) wind_topic_ = _sdf->GetElement("windTopicName")->Get<std::string>();
116  if (_sdf->HasElement("wrenchTopic")) wrench_topic_ = _sdf->GetElement("wrenchTopic")->Get<std::string>();
117  if (_sdf->HasElement("frameId")) frame_id_= _sdf->GetElement("frameId")->Get<std::string>();
118 
119  // Make sure the ROS node for Gazebo has already been initialized
120  if (!ros::isInitialized())
121  {
122  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
123  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
124  return;
125  }
126 
128 
129  // get model parameters
131  gzwarn << "[quadrotor_propulsion] Could not properly configure the aerodynamics plugin. Make sure you loaded the parameter file." << std::endl;
132  return;
133  }
134 
135  // subscribe command
136  if (!wind_topic_.empty())
137  {
140  ops.initByFullCallbackType<const geometry_msgs::Vector3 &>(
141  wind_topic_, 1,
142  boost::bind(&QuadrotorAerodynamics::setWind, &model_, _1)
143  );
145  }
146 
147  // advertise wrench
148  if (!wrench_topic_.empty())
149  {
152  ops.init<geometry_msgs::WrenchStamped>(wrench_topic_, 10);
154  }
155 
156  // callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorAerodynamics::QueueThread,this ) );
157 
158  // New Mechanism for Updating every World Cycle
159  // Listen to the update event. This event is broadcast every
160  // simulation iteration.
161  updateConnection = event::Events::ConnectWorldUpdateBegin(
162  boost::bind(&GazeboQuadrotorAerodynamics::Update, this));
163 }
164 
166 // Update the controller
168 {
169  // Get simulator time
170 #if (GAZEBO_MAJOR_VERSION >= 8)
171  Time current_time = world->SimTime();
172 #else
173  Time current_time = world->GetSimTime();
174 #endif
175  Time dt = current_time - last_time_;
176  last_time_ = current_time;
177  if (dt <= 0.0) return;
178 
179  // Get new commands/state
181 
182  // fill input vector u for drag model
183  geometry_msgs::Quaternion orientation;
184 #if (GAZEBO_MAJOR_VERSION >= 8)
185  fromQuaternion(link->WorldPose().Rot(), orientation);
186 #else
187  fromQuaternion(link->GetWorldPose().rot, orientation);
188 #endif
189  model_.setOrientation(orientation);
190 
191  geometry_msgs::Twist twist;
192 #if (GAZEBO_MAJOR_VERSION >= 8)
193  fromVector(link->WorldLinearVel(), twist.linear);
194  fromVector(link->WorldAngularVel(), twist.angular);
195 #else
196  fromVector(link->GetWorldLinearVel(), twist.linear);
197  fromVector(link->GetWorldAngularVel(), twist.angular);
198 #endif
199  model_.setTwist(twist);
200 
201  // update the model
202  model_.update(dt.Double());
203 
204  // get wrench from model
205 #if (GAZEBO_MAJOR_VERSION >= 8)
206  ignition::math::Vector3d force, torque;
207 #else
208  math::Vector3 force, torque;
209 #endif
210  toVector(model_.getWrench().force, force);
211  toVector(model_.getWrench().torque, torque);
212 
213  // publish wrench
214  if (wrench_publisher_) {
215  geometry_msgs::WrenchStamped wrench_msg;
216  wrench_msg.header.stamp = ros::Time(current_time.sec, current_time.nsec);
217  wrench_msg.header.frame_id = frame_id_;
218  wrench_msg.wrench = model_.getWrench();
219  wrench_publisher_.publish(wrench_msg);
220  }
221 
222  // set force and torque in gazebo
223  link->AddRelativeForce(force);
224 #if (GAZEBO_MAJOR_VERSION >= 8)
225  link->AddRelativeTorque(torque - link->GetInertial()->CoG().Cross(force));
226 #else
227  link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().Cross(force));
228 #endif
229 }
230 
232 // Reset the controller
234 {
235  model_.reset();
236 }
237 
239 // custom callback queue thread
241 {
242  static const double timeout = 0.01;
243 
244  while (node_handle_->ok())
245  {
247  }
248 }
249 
250 // Register this plugin with the simulator
251 GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorAerodynamics)
252 
253 } // namespace gazebo
void initByFullCallbackType(const std::string &_topic, uint32_t _queue_size, const boost::function< void(P)> &_callback, const boost::function< boost::shared_ptr< typename ParameterAdapter< P >::Message >(void)> &factory_fn=DefaultMessageCreator< typename ParameterAdapter< P >::Message >())
void publish(const boost::shared_ptr< M > &message) const
void setWind(const geometry_msgs::Vector3 &wind)
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL bool isInitialized()
const geometry_msgs::Wrench & getWrench() const
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
void setOrientation(const geometry_msgs::Quaternion &orientation)
void setTwist(const geometry_msgs::Twist &twist)
static void fromVector(const Vector &vector, Message &msg)
bool configure(const ros::NodeHandle &param=ros::NodeHandle("~"))
#define ROS_FATAL_STREAM(args)
physics::LinkPtr link
The link referred to by this plugin.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static void fromQuaternion(const Quaternion &quaternion, Message &msg)
static void toQuaternion(const Message &msg, Quaternion &quaternion)
bool ok() const
physics::WorldPtr world
The parent World.
hector_quadrotor_model::QuadrotorAerodynamics model_
CallbackQueueInterface * callback_queue
static void toVector(const Message &msg, Vector &vector)
CallbackQueueInterface * callback_queue


hector_quadrotor_gazebo_plugins
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:36:58