quadrotor_aerodynamics.h
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 
29 #ifndef HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H
30 #define HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H
31 
32 #include <geometry_msgs/Quaternion.h>
33 #include <geometry_msgs/Twist.h>
34 #include <geometry_msgs/Vector3.h>
35 #include <geometry_msgs/Wrench.h>
36 
37 #include <ros/node_handle.h>
38 
39 #include <boost/thread/mutex.hpp>
40 
41 namespace hector_quadrotor_model
42 {
43 
45 public:
48 
49  bool configure(const ros::NodeHandle &param = ros::NodeHandle("~"));
50  void reset();
51  void update(double dt);
52 
53  void setOrientation(const geometry_msgs::Quaternion& orientation);
54  void setTwist(const geometry_msgs::Twist& twist);
55  void setBodyTwist(const geometry_msgs::Twist& twist);
56  void setWind(const geometry_msgs::Vector3& wind);
57 
58  const geometry_msgs::Wrench& getWrench() const { return wrench_; }
59 
60  void f(const double uin[6], double dt, double y[6]) const;
61 
62 private:
63  geometry_msgs::Quaternion orientation_;
64  geometry_msgs::Twist twist_;
65  geometry_msgs::Vector3 wind_;
66 
67  geometry_msgs::Wrench wrench_;
68 
69  boost::mutex mutex_;
70 
71  class DragModel;
73 };
74 
75 }
76 
77 #endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H
bool param(const std::string &param_name, T &param_val, const T &default_val)
void setWind(const geometry_msgs::Vector3 &wind)
void f(const double uin[6], double dt, double y[6]) const
const geometry_msgs::Wrench & getWrench() const
void setOrientation(const geometry_msgs::Quaternion &orientation)
void setTwist(const geometry_msgs::Twist &twist)
bool configure(const ros::NodeHandle &param=ros::NodeHandle("~"))
void setBodyTwist(const geometry_msgs::Twist &twist)


hector_quadrotor_model
Author(s): Johannes Meyer , Alexander Sendobry
autogenerated on Mon Jun 10 2019 13:36:56