gazebo_quadrotor_simple_controller.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_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H
30 #define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H
31 
32 #include <gazebo/common/Plugin.hh>
33 
34 #include <ros/callback_queue.h>
35 #include <ros/ros.h>
36 
37 #include <geometry_msgs/Twist.h>
38 #include <sensor_msgs/Imu.h>
39 #include <nav_msgs/Odometry.h>
40 #include <std_srvs/Empty.h>
41 
43 
44 namespace gazebo
45 {
46 
47 class GazeboQuadrotorSimpleController : public ModelPlugin
48 {
49 public:
52 
53 protected:
54  virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
55  virtual void Update();
56  virtual void Reset();
57 
58 private:
60  physics::WorldPtr world;
61 
63  physics::LinkPtr link;
64 
71 
74 
75  // void CallbackQueueThread();
76  // boost::mutex lock_;
77  // boost::thread callback_queue_thread_;
78 
79  geometry_msgs::Twist velocity_command_;
80  void VelocityCallback(const geometry_msgs::TwistConstPtr&);
81  void ImuCallback(const sensor_msgs::ImuConstPtr&);
82  void StateCallback(const nav_msgs::OdometryConstPtr&);
83 
84  bool EngageCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
85  bool ShutdownCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
86 
88 #if (GAZEBO_MAJOR_VERSION >= 8)
89  ignition::math::Pose3d pose;
90  ignition::math::Vector3d euler, velocity, acceleration, angular_velocity;
91 #else
92  math::Pose pose;
94 #endif
95 
96  std::string link_name_;
97  std::string namespace_;
98  std::string velocity_topic_;
99  std::string imu_topic_;
100  std::string state_topic_;
101  std::string wrench_topic_;
102  double max_force_;
103 
104  bool running_;
106 
108  public:
109  PIDController();
110  virtual ~PIDController();
111  virtual void Load(sdf::ElementPtr _sdf, const std::string& prefix = "");
112 
113  double gain_p;
114  double gain_i;
115  double gain_d;
117  double limit;
118 
119  double input;
120  double dinput;
121  double output;
122  double p, i, d;
123 
124  double update(double input, double x, double dx, double dt);
125  void reset();
126  };
127 
128  struct Controllers {
135  } controllers_;
136 
137 #if (GAZEBO_MAJOR_VERSION >= 8)
138  ignition::math::Vector3d inertia;
139 #else
140  math::Vector3 inertia;
141 #endif
142  double mass;
143 
144 #if (GAZEBO_MAJOR_VERSION >= 8)
145  ignition::math::Vector3d force, torque;
146 #else
147  math::Vector3 force, torque;
148 #endif
149 
151  event::ConnectionPtr updateConnection;
152 };
153 
154 }
155 
156 #endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H
physics::LinkPtr link
The link referred to by this plugin.
double update(double input, double x, double dx, double dt)
struct gazebo::GazeboQuadrotorSimpleController::Controllers controllers_
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix="")
void VelocityCallback(const geometry_msgs::TwistConstPtr &)
bool EngageCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
bool ShutdownCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void StateCallback(const nav_msgs::OdometryConstPtr &)


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