gazebo_quadrotor_propulsion.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 <rosgraph_msgs/Clock.h>
36 #include <geometry_msgs/WrenchStamped.h>
37 
38 #if (GAZEBO_MAJOR_VERSION >= 8)
39 namespace hector_quadrotor_model {
40 
41 template <typename Message, typename T> static inline void toVector(const Message& msg, ignition::math::Vector3<T>& vector)
42 {
43  vector.X() = msg.x;
44  vector.Y() = msg.y;
45  vector.Z() = msg.z;
46 }
47 
48 template <typename Message, typename T> static inline void fromVector(const ignition::math::Vector3<T>& vector, Message& msg)
49 {
50  msg.x = vector.X();
51  msg.y = vector.Y();
52  msg.z = vector.Z();
53 }
54 
55 template <typename Message, typename T> static inline void toQuaternion(const Message& msg, ignition::math::Quaternion<T>& quaternion)
56 {
57  quaternion.W() = msg.w;
58  quaternion.X() = msg.x;
59  quaternion.Y() = msg.y;
60  quaternion.Z() = msg.z;
61 }
62 
63 template <typename Message, typename T> static inline void fromQuaternion(const ignition::math::Quaternion<T>& quaternion, Message& msg)
64 {
65  msg.w = quaternion.W();
66  msg.x = quaternion.X();
67  msg.y = quaternion.Y();
68  msg.z = quaternion.Z();
69 }
70 
71 } // namespace hector_quadrotor_model
72 #endif
73 
74 namespace gazebo {
75 
76 using namespace common;
77 using namespace hector_quadrotor_model;
78 
79 GazeboQuadrotorPropulsion::GazeboQuadrotorPropulsion()
80  : node_handle_(0)
81 {
82 }
83 
85 {
86 #if (GAZEBO_MAJOR_VERSION < 8)
87  event::Events::DisconnectWorldUpdateBegin(updateConnection);
88 #endif
89  updateConnection.reset();
90 
91  if (node_handle_) {
93  if (callback_queue_thread_.joinable())
95  delete node_handle_;
96  }
97 }
98 
100 // Load the controller
101 void GazeboQuadrotorPropulsion::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
102 {
103  world = _model->GetWorld();
104  link = _model->GetLink();
105 
106  // default parameters
107  namespace_.clear();
108  param_namespace_ = "quadrotor_propulsion";
109  trigger_topic_ = "quadro/trigger";
110  command_topic_ = "command/motor";
111  pwm_topic_ = "motor_pwm";
112  wrench_topic_ = "propulsion/wrench";
113  supply_topic_ = "supply";
114  status_topic_ = "motor_status";
117  frame_id_ = link->GetName();
118 
119  // load parameters
120  if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>();
121  if (_sdf->HasElement("paramNamespace")) param_namespace_ = _sdf->GetElement("paramNamespace")->Get<std::string>();
122  if (_sdf->HasElement("triggerTopic")) trigger_topic_ = _sdf->GetElement("triggerTopic")->Get<std::string>();
123  if (_sdf->HasElement("topicName")) command_topic_ = _sdf->GetElement("topicName")->Get<std::string>();
124  if (_sdf->HasElement("pwmTopicName")) pwm_topic_ = _sdf->GetElement("pwmTopicName")->Get<std::string>();
125  if (_sdf->HasElement("wrenchTopic")) wrench_topic_ = _sdf->GetElement("wrenchTopic")->Get<std::string>();
126  if (_sdf->HasElement("supplyTopic")) supply_topic_ = _sdf->GetElement("supplyTopic")->Get<std::string>();
127  if (_sdf->HasElement("statusTopic")) status_topic_ = _sdf->GetElement("statusTopic")->Get<std::string>();
128  if (_sdf->HasElement("frameId")) frame_id_= _sdf->GetElement("frameId")->Get<std::string>();
129 
130  if (_sdf->HasElement("voltageTopicName")) {
131  gzwarn << "[quadrotor_propulsion] Plugin parameter 'voltageTopicName' is deprecated! Plese change your config to use "
132  << "'topicName' for MotorCommand messages or 'pwmTopicName' for MotorPWM messages." << std::endl;
133  pwm_topic_ = _sdf->GetElement("voltageTopicName")->Get<std::string>();
134  }
135 
136  // set control timing parameters
137  controlTimer.Load(world, _sdf, "control");
138  motorStatusTimer.Load(world, _sdf, "motorStatus");
139  if (_sdf->HasElement("controlTolerance")) control_tolerance_.fromSec(_sdf->GetElement("controlTolerance")->Get<double>());
140  if (_sdf->HasElement("controlDelay")) control_delay_.fromSec(_sdf->GetElement("controlDelay")->Get<double>());
141 
142  // set initial supply voltage
143  if (_sdf->HasElement("supplyVoltage")) model_.setInitialSupplyVoltage(_sdf->GetElement("supplyVoltage")->Get<double>());
144 
145  // Make sure the ROS node for Gazebo has already been initialized
146  if (!ros::isInitialized())
147  {
148  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
149  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
150  return;
151  }
152 
154 
155  // get model parameters
157  gzwarn << "[quadrotor_propulsion] Could not properly configure the propulsion plugin. Make sure you loaded the parameter file." << std::endl;
158  return;
159  }
160 
161  // publish trigger
162  if (!trigger_topic_.empty())
163  {
166  ops.init<rosgraph_msgs::Clock>(trigger_topic_, 10);
168  }
169 
170  // subscribe voltage command
171  if (!command_topic_.empty())
172  {
175  ops.init<hector_uav_msgs::MotorCommand>(command_topic_, 1, boost::bind(&QuadrotorPropulsion::addCommandToQueue, &model_, _1));
177  }
178 
179  // subscribe pwm command
180  if (!pwm_topic_.empty())
181  {
184  ops.init<hector_uav_msgs::MotorPWM>(pwm_topic_, 1, boost::bind(&QuadrotorPropulsion::addPWMToQueue, &model_, _1));
186  }
187 
188  // advertise wrench
189  if (!wrench_topic_.empty())
190  {
193  ops.init<geometry_msgs::WrenchStamped>(wrench_topic_, 10);
195  }
196 
197  // advertise and latch supply
198  if (!supply_topic_.empty())
199  {
202  ops.latch = true;
203  ops.init<hector_uav_msgs::Supply>(supply_topic_, 10);
205  supply_publisher_.publish(model_.getSupply());
206  }
207 
208  // advertise motor_status
209  if (!status_topic_.empty())
210  {
213  ops.init<hector_uav_msgs::MotorStatus>(status_topic_, 10);
215  }
216 
217  // callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorPropulsion::QueueThread,this ) );
218 
219  Reset();
220 
221  // New Mechanism for Updating every World Cycle
222  // Listen to the update event. This event is broadcast every
223  // simulation iteration.
224  updateConnection = event::Events::ConnectWorldUpdateBegin(
225  boost::bind(&GazeboQuadrotorPropulsion::Update, this));
226 }
227 
229 // Update the controller
231 {
232  // Get simulator time
233 #if (GAZEBO_MAJOR_VERSION >= 8)
234  Time current_time = world->SimTime();
235 #else
236  Time current_time = world->GetSimTime();
237 #endif
238  Time dt = current_time - last_time_;
239  last_time_ = current_time;
240  if (dt <= 0.0) return;
241 
242  // Send trigger
243  bool trigger = controlTimer.getUpdatePeriod() > 0.0 ? controlTimer.update() : false;
244  if (trigger && trigger_publisher_) {
245  rosgraph_msgs::Clock clock;
246  clock.clock = ros::Time(current_time.sec, current_time.nsec);
248 
249  ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Sent a trigger message at t = " << current_time.Double() << " (dt = " << (current_time - last_trigger_time_).Double() << ")");
250  last_trigger_time_ = current_time;
251  }
252 
253  // Get new commands/state
255 
256  // Process input queue
257  model_.processQueue(ros::Time(current_time.sec, current_time.nsec), control_tolerance_, control_delay_, (model_.getMotorStatus().on && trigger) ? ros::WallDuration(1.0) : ros::WallDuration(), &callback_queue_);
258 
259  // fill input vector u for propulsion model
260  geometry_msgs::Twist twist;
261 #if (GAZEBO_MAJOR_VERSION >= 8)
262  fromVector(link->RelativeLinearVel(), twist.linear);
263  fromVector(link->RelativeAngularVel(), twist.angular);
264 #else
265  fromVector(link->GetRelativeLinearVel(), twist.linear);
266  fromVector(link->GetRelativeAngularVel(), twist.angular);
267 #endif
268  model_.setTwist(twist);
269 
270  // update the model
271  model_.update(dt.Double());
272 
273  // get wrench from model
274 #if (GAZEBO_MAJOR_VERSION >= 8)
275  ignition::math::Vector3d force, torque;
276 #else
277  math::Vector3 force, torque;
278 #endif
279  toVector(model_.getWrench().force, force);
280  toVector(model_.getWrench().torque, torque);
281 
282  // publish wrench
283  if (wrench_publisher_) {
284  geometry_msgs::WrenchStamped wrench_msg;
285  wrench_msg.header.stamp = ros::Time(current_time.sec, current_time.nsec);
286  wrench_msg.header.frame_id = frame_id_;
287  wrench_msg.wrench = model_.getWrench();
288  wrench_publisher_.publish(wrench_msg);
289  }
290 
291  // publish motor status
292  if (motor_status_publisher_ && motorStatusTimer.update() /* && current_time >= last_motor_status_time_ + control_period_ */) {
293  hector_uav_msgs::MotorStatus motor_status = model_.getMotorStatus();
294  motor_status.header.stamp = ros::Time(current_time.sec, current_time.nsec);
295  motor_status_publisher_.publish(motor_status);
296  last_motor_status_time_ = current_time;
297  }
298 
299  // publish supply
300  if (supply_publisher_ && current_time >= last_supply_time_ + 1.0) {
302  last_supply_time_ = current_time;
303  }
304 
305  // set force and torque in gazebo
306  link->AddRelativeForce(force);
307 #if (GAZEBO_MAJOR_VERSION >= 8)
308  link->AddRelativeTorque(torque - link->GetInertial()->CoG().Cross(force));
309 #else
310  link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().Cross(force));
311 #endif
312 }
313 
315 // Reset the controller
317 {
318  model_.reset();
319  last_time_ = Time();
320  last_trigger_time_ = Time();
321  last_motor_status_time_ = Time();
322  last_supply_time_ = Time();
323 }
324 
326 // custom callback queue thread
328 {
329  static const double timeout = 0.01;
330 
331  while (node_handle_->ok())
332  {
334  }
335 }
336 
337 // Register this plugin with the simulator
338 GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorPropulsion)
339 
340 } // namespace gazebo
bool configure(const ros::NodeHandle &param=ros::NodeHandle("~"))
hector_quadrotor_model::QuadrotorPropulsion model_
const hector_uav_msgs::MotorStatus & getMotorStatus() const
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string &_prefix="update")
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
bool processQueue(const ros::Time &timestamp, const ros::Duration &tolerance=ros::Duration(), const ros::Duration &delay=ros::Duration(), const ros::WallDuration &wait=ros::WallDuration(), ros::CallbackQueue *callback_queue=0)
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
const hector_uav_msgs::Supply & getSupply() const
physics::LinkPtr link
The link referred to by this plugin.
virtual bool update()
static void fromVector(const Vector &vector, Message &msg)
common::Time const & getUpdatePeriod() const
#define ROS_FATAL_STREAM(args)
Duration & fromSec(double t)
void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr &pwm)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
static void fromQuaternion(const Quaternion &quaternion, Message &msg)
physics::WorldPtr world
The parent World.
static void toQuaternion(const Message &msg, Quaternion &quaternion)
void init(const std::string &_topic, uint32_t _queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &_callback, const boost::function< boost::shared_ptr< M >(void)> &factory_fn=DefaultMessageCreator< M >())
bool ok() const
CallbackQueueInterface * callback_queue
static void toVector(const Message &msg, Vector &vector)
CallbackQueueInterface * callback_queue
void setTwist(const geometry_msgs::Twist &twist)
void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr &command)


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