$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_PROPULSION_H 00030 #define HECTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_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 <hector_uav_msgs/MotorStatus.h> 00043 #include <hector_uav_msgs/MotorPWM.h> 00044 #include <geometry_msgs/Wrench.h> 00045 #include <geometry_msgs/Vector3.h> 00046 00047 #include <boost/thread.hpp> 00048 #include <list> 00049 00050 namespace gazebo 00051 { 00052 00053 class GazeboQuadrotorPropulsion : public Controller 00054 { 00055 public: 00056 GazeboQuadrotorPropulsion(Entity *parent); 00057 virtual ~GazeboQuadrotorPropulsion(); 00058 00059 protected: 00060 virtual void LoadChild(XMLConfigNode *node); 00061 virtual void InitChild(); 00062 virtual void UpdateChild(); 00063 virtual void FiniChild(); 00064 virtual void ResetChild(); 00065 00066 private: 00067 Model *parent_; 00068 Body *body_; 00069 00070 ros::NodeHandle* node_handle_; 00071 ros::CallbackQueue callback_queue_; 00072 boost::thread callback_queue_thread_; 00073 void QueueThread(); 00074 00075 ros::Subscriber voltage_subscriber_; 00076 ros::Publisher wrench_publisher_; 00077 ros::Publisher motor_status_publisher_; 00078 00079 hector_uav_msgs::MotorPWMConstPtr motor_voltage_; 00080 std::list<hector_uav_msgs::MotorPWMConstPtr> new_motor_voltages_; 00081 geometry_msgs::Wrench wrench_; 00082 hector_uav_msgs::MotorStatus motor_status_; 00083 void CommandCallback(const hector_uav_msgs::MotorPWMConstPtr&); 00084 00085 Vector3 velocity, rate; 00086 00087 ParamT<std::string> *body_name_; 00088 ParamT<std::string> *namespace_; 00089 ParamT<std::string> *param_namespace_; 00090 ParamT<Time> *control_rate_; 00091 ParamT<std::string> *voltage_topic_; 00092 ParamT<std::string> *wrench_topic_; 00093 ParamT<std::string> *status_topic_; 00094 ParamT<Time> *control_delay_param_; 00095 Time control_delay_; 00096 Time control_tolerance_; 00097 00098 00099 class PropulsionModel; 00100 PropulsionModel *propulsion_model_; 00101 00102 Time control_period_; 00103 Time last_control_time_; 00104 Time last_motor_status_time_; 00105 00106 boost::condition command_condition_; 00107 boost::mutex command_mutex_; 00108 }; 00109 00110 } 00111 00112 #endif // HECTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_H