$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_gazebo_plugins/gazebo_ros_magnetic.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_magnetic", GazeboRosMagnetic) 00044 00045 GazeboRosMagnetic::GazeboRosMagnetic(Entity *parent) 00046 : Controller(parent) 00047 , sensor_model_(parameters) 00048 { 00049 parent_ = dynamic_cast<Model*>(parent); 00050 if (!parent_) gzthrow("GazeboRosMagnetic 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 topic_ = new ParamT<std::string>("topicName", "magnetic", false); 00063 00064 magnitude_ = new ParamT<double>("magnitude", 1.0, false); 00065 reference_heading_ = new ParamT<double>("referenceHeading", 0.0, false); 00066 declination_ = new ParamT<double>("declination", 0.0, false); 00067 inclination_ = new ParamT<double>("inclination", 60.0, false); 00068 Param::End(); 00069 } 00070 00072 // Destructor 00073 GazeboRosMagnetic::~GazeboRosMagnetic() 00074 { 00075 delete namespace_; 00076 delete body_name_; 00077 delete topic_; 00078 delete magnitude_; 00079 delete reference_heading_; 00080 delete declination_; 00081 delete inclination_; 00082 } 00083 00085 // Load the controller 00086 void GazeboRosMagnetic::LoadChild(XMLConfigNode *node) 00087 { 00088 namespace_->Load(node); 00089 body_name_->Load(node); 00090 00091 // assert that the body by body_name_ exists 00092 body_ = dynamic_cast<Body*>(parent_->GetBody(**body_name_)); 00093 if (!body_) gzthrow("gazebo_quadrotor_simple_controller plugin error: body_name_: " << **body_name_ << "does not exist\n"); 00094 00095 magnetic_field_.header.frame_id = body_->GetName(); 00096 00097 topic_->Load(node); 00098 00099 magnitude_->Load(node); 00100 reference_heading_->Load(node); 00101 declination_->Load(node); 00102 inclination_->Load(node); 00103 00104 reference_heading_->SetValue(**reference_heading_ * M_PI/180.0); // convert to radians 00105 declination_->SetValue(**declination_ * M_PI/180.0); // convert to radians 00106 inclination_->SetValue(**inclination_ * M_PI/180.0); // convert to radians 00107 00108 // Note: Gazebo uses NorthWestUp coordinate system, heading and declination are compass headings 00109 magnetic_field_world_.x = **magnitude_ * cos(**inclination_) * cos(**reference_heading_ - **declination_); 00110 magnetic_field_world_.y = **magnitude_ * sin(**reference_heading_ - **declination_); 00111 magnetic_field_world_.z = **magnitude_ * -sin(**inclination_) * cos(**reference_heading_ - **declination_); 00112 00113 sensor_model_.Load(node); 00114 } 00115 00117 // Initialize the controller 00118 void GazeboRosMagnetic::InitChild() 00119 { 00120 node_handle_ = new ros::NodeHandle(**namespace_); 00121 publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(**topic_, 10); 00122 } 00123 00125 // Update the controller 00126 void GazeboRosMagnetic::UpdateChild() 00127 { 00128 Time sim_time = Simulator::Instance()->GetSimTime(); 00129 double dt = (sim_time - lastUpdate).Double(); 00130 00131 Pose3d pose = body_->GetWorldPose(); 00132 Vector3 field = sensor_model_(pose.rot.RotateVectorReverse(magnetic_field_world_), dt); 00133 00134 magnetic_field_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec); 00135 magnetic_field_.vector.x = field.x; 00136 magnetic_field_.vector.y = field.y; 00137 magnetic_field_.vector.z = field.z; 00138 00139 publisher_.publish(magnetic_field_); 00140 } 00141 00143 // Finalize the controller 00144 void GazeboRosMagnetic::FiniChild() 00145 { 00146 node_handle_->shutdown(); 00147 delete node_handle_; 00148 } 00149