$search
00001 //================================================================================================= 00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #ifndef HECTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H 00030 #define HECTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H 00031 00032 #include <gazebo/Controller.hh> 00033 #include <gazebo/Entity.hh> 00034 #include <gazebo/Model.hh> 00035 #include <gazebo/Body.hh> 00036 #include <gazebo/Param.hh> 00037 #include <gazebo/Time.hh> 00038 00039 #include <ros/callback_queue.h> 00040 #include <ros/ros.h> 00041 00042 #include <geometry_msgs/Twist.h> 00043 #include <sensor_msgs/Imu.h> 00044 #include <nav_msgs/Odometry.h> 00045 00046 namespace gazebo 00047 { 00048 00049 class GazeboQuadrotorSimpleController : public Controller 00050 { 00051 public: 00052 GazeboQuadrotorSimpleController(Entity *parent); 00053 virtual ~GazeboQuadrotorSimpleController(); 00054 00055 protected: 00056 virtual void LoadChild(XMLConfigNode *node); 00057 virtual void InitChild(); 00058 virtual void UpdateChild(); 00059 virtual void FiniChild(); 00060 virtual void ResetChild(); 00061 00062 private: 00063 Model *parent_; 00064 Body *body_; 00065 00066 ros::NodeHandle* node_handle_; 00067 ros::CallbackQueue callback_queue_; 00068 ros::Subscriber velocity_subscriber_; 00069 ros::Subscriber imu_subscriber_; 00070 ros::Subscriber state_subscriber_; 00071 00072 // void CallbackQueueThread(); 00073 // boost::mutex lock_; 00074 // boost::thread callback_queue_thread_; 00075 00076 geometry_msgs::Twist velocity_command_; 00077 void VelocityCallback(const geometry_msgs::TwistConstPtr&); 00078 void ImuCallback(const sensor_msgs::ImuConstPtr&); 00079 void StateCallback(const nav_msgs::OdometryConstPtr&); 00080 00081 ros::Time state_stamp; 00082 Pose3d pose; 00083 Vector3 euler, velocity, acceleration, angular_velocity; 00084 00085 ParamT<std::string> *body_name_param_; 00086 std::string body_name_; 00087 ParamT<std::string> *namespace_param_; 00088 std::string namespace_; 00089 ParamT<std::string> *velocity_topic_param_; 00090 std::string velocity_topic_; 00091 ParamT<std::string> *imu_topic_param_; 00092 std::string imu_topic_; 00093 ParamT<std::string> *state_topic_param_; 00094 std::string state_topic_; 00095 ParamT<double> *max_force_param_; 00096 double max_force_; 00097 00098 class PIDController { 00099 public: 00100 PIDController(std::vector<Param*>& parameters); 00101 virtual ~PIDController(); 00102 virtual void LoadChild(XMLConfigNode *node); 00103 00104 ParamT<double> *gain_p_param_; 00105 double gain_p; 00106 ParamT<double> *gain_i_param_; 00107 double gain_i; 00108 ParamT<double> *gain_d_param_; 00109 double gain_d; 00110 ParamT<double> *time_constant_param_; 00111 double time_constant; 00112 ParamT<double> *limit_param_; 00113 double limit; 00114 00115 double input; 00116 double dinput; 00117 double output; 00118 double p, i, d; 00119 00120 double update(double input, double x, double dx, double dt); 00121 void reset(); 00122 }; 00123 00124 struct Controllers { 00125 Controllers(std::vector<Param*>& parameters) : roll(parameters), pitch(parameters), yaw(parameters), velocity_x(parameters), velocity_y(parameters), velocity_z(parameters) {} 00126 PIDController roll; 00127 PIDController pitch; 00128 PIDController yaw; 00129 PIDController velocity_x; 00130 PIDController velocity_y; 00131 PIDController velocity_z; 00132 } controllers_; 00133 00134 Vector3 inertia; 00135 double mass; 00136 }; 00137 00138 } 00139 00140 #endif // HECTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H