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/common/Plugin.hh> 00033 00034 #include <ros/callback_queue.h> 00035 #include <ros/ros.h> 00036 00037 #include <hector_uav_msgs/Supply.h> 00038 #include <hector_uav_msgs/MotorStatus.h> 00039 #include <hector_uav_msgs/MotorPWM.h> 00040 #include <geometry_msgs/Wrench.h> 00041 00042 #include <boost/thread.hpp> 00043 #include <boost/thread/mutex.hpp> 00044 #include <boost/thread/condition.hpp> 00045 #include <queue> 00046 00047 #include <hector_gazebo_plugins/update_timer.h> 00048 00049 namespace gazebo 00050 { 00051 00052 class GazeboQuadrotorPropulsion : public ModelPlugin 00053 { 00054 public: 00055 GazeboQuadrotorPropulsion(); 00056 virtual ~GazeboQuadrotorPropulsion(); 00057 00058 protected: 00059 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); 00060 virtual void Reset(); 00061 virtual void Update(); 00062 00063 private: 00065 physics::WorldPtr world; 00066 00068 physics::LinkPtr link; 00069 00070 ros::NodeHandle* node_handle_; 00071 ros::CallbackQueue callback_queue_; 00072 boost::thread callback_queue_thread_; 00073 void QueueThread(); 00074 00075 ros::Publisher trigger_publisher_; 00076 ros::Subscriber voltage_subscriber_; 00077 ros::Publisher wrench_publisher_; 00078 ros::Publisher supply_publisher_; 00079 ros::Publisher motor_status_publisher_; 00080 00081 hector_uav_msgs::MotorPWMConstPtr motor_voltage_; 00082 std::queue<hector_uav_msgs::MotorPWMConstPtr> new_motor_voltages_; 00083 geometry_msgs::Wrench wrench_; 00084 hector_uav_msgs::Supply supply_; 00085 hector_uav_msgs::MotorStatus motor_status_; 00086 void CommandCallback(const hector_uav_msgs::MotorPWMConstPtr&); 00087 00088 math::Vector3 velocity, rate; 00089 00090 std::string body_name_; 00091 std::string namespace_; 00092 std::string param_namespace_; 00093 std::string trigger_topic_; 00094 std::string voltage_topic_; 00095 std::string wrench_topic_; 00096 std::string supply_topic_; 00097 std::string status_topic_; 00098 common::Time control_delay_; 00099 common::Time control_tolerance_; 00100 00101 class PropulsionModel; 00102 PropulsionModel *propulsion_model_; 00103 00104 common::Time last_time_; 00105 common::Time last_trigger_time_; 00106 common::Time last_control_time_; 00107 common::Time last_motor_status_time_; 00108 00109 boost::condition command_condition_; 00110 boost::mutex command_mutex_; 00111 00112 // Pointer to the update event connection 00113 event::ConnectionPtr updateConnection; 00114 00115 UpdateTimer controlTimer; 00116 }; 00117 00118 } 00119 00120 #endif // HECTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_H