quadrotor_propulsion.h
Go to the documentation of this file.
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_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H
00030 #define HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H
00031 
00032 #include <hector_uav_msgs/Supply.h>
00033 #include <hector_uav_msgs/MotorStatus.h>
00034 #include <hector_uav_msgs/MotorCommand.h>
00035 #include <hector_uav_msgs/MotorPWM.h>
00036 #include <geometry_msgs/Twist.h>
00037 #include <geometry_msgs/Wrench.h>
00038 
00039 #include <ros/forwards.h>
00040 #include <ros/node_handle.h>
00041 #include <ros/time.h>
00042 
00043 #include <queue>
00044 
00045 #include <boost/thread/mutex.hpp>
00046 #include <boost/thread/condition.hpp>
00047 
00048 namespace hector_quadrotor_model
00049 {
00050 
00051 class QuadrotorPropulsion
00052 {
00053 public:
00054   QuadrotorPropulsion();
00055   ~QuadrotorPropulsion();
00056 
00057   bool configure(const ros::NodeHandle &param = ros::NodeHandle("~"));
00058   void reset();
00059   void update(double dt);
00060 
00061   void engage();
00062   void shutdown();
00063 
00064   void setTwist(const geometry_msgs::Twist& twist);
00065   void setVoltage(const hector_uav_msgs::MotorPWM& command);
00066 
00067   const geometry_msgs::Wrench& getWrench() const { return wrench_; }
00068   const hector_uav_msgs::Supply& getSupply() const { return supply_; }
00069   const hector_uav_msgs::MotorStatus& getMotorStatus() const { return motor_status_; }
00070 
00071   void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr& command);
00072   void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr& pwm);
00073   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);
00074 
00075   void f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const;
00076 
00077   void setInitialSupplyVoltage(double voltage) { initial_voltage_ = voltage; }
00078 
00079 private:
00080   geometry_msgs::Wrench wrench_;
00081   hector_uav_msgs::Supply supply_;
00082   hector_uav_msgs::MotorStatus motor_status_;
00083   ros::Time last_command_time_;
00084 
00085   double initial_voltage_;
00086 
00087   std::queue<hector_uav_msgs::MotorPWMConstPtr> command_queue_;
00088   boost::mutex command_queue_mutex_;
00089   boost::condition command_condition_;
00090 
00091   boost::mutex mutex_;
00092 
00093   class PropulsionModel;
00094   PropulsionModel *propulsion_model_;
00095 };
00096 
00097 }
00098 
00099 #endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H


hector_quadrotor_model
Author(s): Johannes Meyer , Alexander Sendobry
autogenerated on Sun Jul 10 2016 04:50:01