$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_sonar.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/GazeboError.hh> 00037 #include <gazebo/ControllerFactory.hh> 00038 00039 #include <limits> 00040 00041 using namespace gazebo; 00042 00043 GZ_REGISTER_DYNAMIC_CONTROLLER("hector_gazebo_ros_sonar", GazeboRosSonar) 00044 00045 GazeboRosSonar::GazeboRosSonar(Entity *parent) 00046 : Controller(parent) 00047 , sensor_model_(parameters) 00048 { 00049 sensor_ = dynamic_cast<RaySensor*>(parent); 00050 if (!sensor_) gzthrow("GazeboRosSonar controller requires a RaySensor 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_param_ = new ParamT<std::string>("robotNamespace", "", false); 00061 topic_param_ = new ParamT<std::string>("topicName", "sonar", false); 00062 frame_id_param_ = new ParamT<std::string>("frameId", "", false); 00063 Param::End(); 00064 } 00065 00067 // Destructor 00068 GazeboRosSonar::~GazeboRosSonar() 00069 { 00070 delete namespace_param_; 00071 delete topic_param_; 00072 delete frame_id_param_; 00073 } 00074 00076 // Load the controller 00077 void GazeboRosSonar::LoadChild(XMLConfigNode *node) 00078 { 00079 namespace_param_->Load(node); 00080 topic_param_->Load(node); 00081 frame_id_param_->Load(node); 00082 00083 sensor_model_.Load(node); 00084 } 00085 00087 // Initialize the controller 00088 void GazeboRosSonar::InitChild() 00089 { 00090 range_.header.frame_id = **frame_id_param_; 00091 range_.radiation_type = sensor_msgs::Range::ULTRASOUND; 00092 range_.field_of_view = std::min(fabs((sensor_->GetMaxAngle() - sensor_->GetMinAngle()).GetAsRadian()), fabs((sensor_->GetVerticalMaxAngle() - sensor_->GetVerticalMinAngle().GetAsRadian()).GetAsRadian())); 00093 range_.max_range = sensor_->GetMaxRange(); 00094 range_.min_range = sensor_->GetMinRange(); 00095 00096 sensor_->SetActive(false); 00097 node_handle_ = new ros::NodeHandle(**namespace_param_); 00098 publisher_ = node_handle_->advertise<sensor_msgs::Range>(**topic_param_, 10); 00099 } 00100 00102 // Update the controller 00103 void GazeboRosSonar::UpdateChild() 00104 { 00105 Time sim_time = Simulator::Instance()->GetSimTime(); 00106 double dt = (sim_time - lastUpdate).Double(); 00107 00108 if (!sensor_->IsActive()) sensor_->SetActive(true); 00109 00110 range_.header.stamp.sec = (Simulator::Instance()->GetSimTime()).sec; 00111 range_.header.stamp.nsec = (Simulator::Instance()->GetSimTime()).nsec; 00112 00113 range_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max(); 00114 int num_ranges = sensor_->GetRangeCount() * sensor_->GetVerticalRangeCount(); 00115 for(int i = 0; i < num_ranges; ++i) { 00116 double ray = sensor_->GetRange(i); 00117 if (ray < range_.range) range_.range = ray; 00118 } 00119 00120 // add Gaussian noise (and limit to min/max range) 00121 if (range_.range < range_.max_range) { 00122 range_.range += sensor_model_.update(dt); 00123 if (range_.range < range_.min_range) range_.range = range_.min_range; 00124 if (range_.range > range_.max_range) range_.range = range_.max_range; 00125 } 00126 00127 publisher_.publish(range_); 00128 } 00129 00131 // Finalize the controller 00132 void GazeboRosSonar::FiniChild() 00133 { 00134 sensor_->SetActive(false); 00135 node_handle_->shutdown(); 00136 delete node_handle_; 00137 } 00138