$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 #include <hector_quadrotor_gazebo_plugins/gazebo_ros_baro.h> 00030 00031 #include <gazebo/Sensor.hh> 00032 #include <gazebo/Global.hh> 00033 #include <gazebo/XMLConfig.hh> 00034 #include <gazebo/Simulator.hh> 00035 #include <gazebo/gazebo.h> 00036 #include <gazebo/World.hh> 00037 #include <gazebo/PhysicsEngine.hh> 00038 #include <gazebo/GazeboError.hh> 00039 #include <gazebo/ControllerFactory.hh> 00040 00041 using namespace gazebo; 00042 00043 GZ_REGISTER_DYNAMIC_CONTROLLER("hector_gazebo_ros_baro", GazeboRosBaro) 00044 00045 GazeboRosBaro::GazeboRosBaro(Entity *parent) 00046 : Controller(parent) 00047 , sensor_model_(parameters) 00048 { 00049 parent_ = dynamic_cast<Model*>(parent); 00050 if (!parent_) gzthrow("GazeboRosBaro controller requires a Model as its parent"); 00051 00052 if (!ros::isInitialized()) 00053 { 00054 int argc = 0; 00055 char** argv = NULL; 00056 ros::init(argc,argv, "gazebo", ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00057 } 00058 00059 Param::Begin(¶meters); 00060 namespace_ = new ParamT<std::string>("robotNamespace", "", false); 00061 body_name_ = new ParamT<std::string>("bodyName", "", true); 00062 frame_id_ = new ParamT<std::string>("frameId", "", false); 00063 height_topic_ = new ParamT<std::string>("topicName", "", false); 00064 altimeter_topic_ = new ParamT<std::string>("altimeterTopicName", "", false); 00065 elevation_ = new ParamT<double>("elevation", 0.0, false);; 00066 qnh_ = new ParamT<double>("qnh", 1013.25, false); 00067 00068 Param::End(); 00069 } 00070 00072 // Destructor 00073 GazeboRosBaro::~GazeboRosBaro() 00074 { 00075 delete namespace_; 00076 delete body_name_; 00077 delete frame_id_; 00078 delete height_topic_; 00079 delete altimeter_topic_; 00080 delete elevation_; 00081 delete qnh_; 00082 } 00083 00085 // Load the controller 00086 void GazeboRosBaro::LoadChild(XMLConfigNode *node) 00087 { 00088 namespace_->Load(node); 00089 body_name_->Load(node); 00090 frame_id_->Load(node); 00091 height_topic_->Load(node); 00092 altimeter_topic_->Load(node); 00093 00094 // assert that the body by body_name_ exists 00095 body_ = dynamic_cast<Body*>(parent_->GetBody(**body_name_)); 00096 if (!body_) gzthrow("gazebo_quadrotor_simple_controller plugin error: body_name_: " << **body_name_ << "does not exist\n"); 00097 00098 elevation_->Load(node); 00099 qnh_->Load(node); 00100 00101 sensor_model_.Load(node); 00102 height_.header.frame_id = **frame_id_; 00103 } 00104 00106 // Initialize the controller 00107 void GazeboRosBaro::InitChild() 00108 { 00109 node_handle_ = new ros::NodeHandle(**namespace_); 00110 if (!(**height_topic_).empty()) { 00111 #ifdef USE_MAV_MSGS 00112 height_publisher_ = node_handle_->advertise<mav_msgs::Height>(**height_topic_, 10); 00113 #else 00114 height_publisher_ = node_handle_->advertise<geometry_msgs::PointStamped>(**height_topic_, 10); 00115 #endif 00116 } 00117 00118 if (!(**altimeter_topic_).empty()) { 00119 altimeter_publisher_ = node_handle_->advertise<hector_uav_msgs::Altimeter>(**altimeter_topic_, 10); 00120 } 00121 } 00122 00124 // Update the controller 00125 void GazeboRosBaro::UpdateChild() 00126 { 00127 Time sim_time = Simulator::Instance()->GetSimTime(); 00128 double dt = (sim_time - lastUpdate).Double(); 00129 00130 Pose3d pose = body_->GetWorldPose(); 00131 double height = sensor_model_(pose.pos.z, dt); 00132 00133 if (height_publisher_) { 00134 #ifdef USE_MAV_MSGS 00135 double previous_height = height_.height; 00136 height_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec); 00137 height_.height = height; 00138 height_.height_variance = sensor_model_.gaussian_noise*sensor_model_.gaussian_noise + sensor_model_.drift*sensor_model_.drift; 00139 height_.climb = dt > 0.0 ? (height_.height - previous_height) / dt : 0.0; 00140 height_.climb_variance = sensor_model_.gaussian_noise*sensor_model_.gaussian_noise; 00141 #else 00142 height_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec); 00143 height_.point.z = height; 00144 #endif 00145 00146 height_publisher_.publish(height_); 00147 } 00148 00149 if (altimeter_publisher_) { 00150 altimeter_.header = height_.header; 00151 altimeter_.altitude = height + **elevation_; 00152 altimeter_.pressure = pow((1.0 - altimeter_.altitude / 44330.0), 5.263157) * **qnh_; 00153 altimeter_.qnh = **qnh_; 00154 altimeter_publisher_.publish(altimeter_); 00155 } 00156 } 00157 00159 // Finalize the controller 00160 void GazeboRosBaro::FiniChild() 00161 { 00162 node_handle_->shutdown(); 00163 delete node_handle_; 00164 } 00165