gazebo_ros_sonar.cpp
Go to the documentation of this file.
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 #include <gazebo/common/Events.hh>
00031 #include <gazebo/physics/physics.hh>
00032 #include <gazebo/sensors/RaySensor.hh>
00033 
00034 #include <limits>
00035 
00036 namespace gazebo {
00037 
00038 GazeboRosSonar::GazeboRosSonar()
00039 {
00040 }
00041 
00043 // Destructor
00044 GazeboRosSonar::~GazeboRosSonar()
00045 {
00046   updateTimer.Disconnect(updateConnection);
00047   sensor_->SetActive(false);
00048 
00049   dynamic_reconfigure_server_.reset();
00050 
00051   node_handle_->shutdown();
00052   delete node_handle_;
00053 }
00054 
00056 // Load the controller
00057 void GazeboRosSonar::Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
00058 {
00059   // Get then name of the parent sensor
00060   sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_sensor);
00061   if (!sensor_)
00062   {
00063     gzthrow("GazeboRosSonar requires a Ray Sensor as its parent");
00064     return;
00065   }
00066 
00067   // Get the world name.
00068   std::string worldName = sensor_->GetWorldName();
00069   world = physics::get_world(worldName);
00070 
00071   // default parameters
00072   namespace_.clear();
00073   topic_ = "sonar";
00074   frame_id_ = "/sonar_link";
00075 
00076   // load parameters
00077   if (_sdf->HasElement("robotNamespace"))
00078     namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
00079 
00080   if (_sdf->HasElement("frameId"))
00081     frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
00082 
00083   if (_sdf->HasElement("topicName"))
00084     topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
00085 
00086   sensor_model_.Load(_sdf);
00087 
00088   range_.header.frame_id = frame_id_;
00089   range_.radiation_type = sensor_msgs::Range::ULTRASOUND;
00090   range_.field_of_view = std::min(fabs((sensor_->GetAngleMax() - sensor_->GetAngleMin()).Radian()), fabs((sensor_->GetVerticalAngleMax() - sensor_->GetVerticalAngleMin()).Radian()));
00091   range_.max_range = sensor_->GetRangeMax();
00092   range_.min_range = sensor_->GetRangeMin();
00093 
00094   // Make sure the ROS node for Gazebo has already been initialized
00095   if (!ros::isInitialized())
00096   {
00097     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00098       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00099     return;
00100   }
00101 
00102   node_handle_ = new ros::NodeHandle(namespace_);
00103   publisher_ = node_handle_->advertise<sensor_msgs::Range>(topic_, 1);
00104 
00105   // setup dynamic_reconfigure server
00106   dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_)));
00107   dynamic_reconfigure_server_->setCallback(boost::bind(&SensorModel::dynamicReconfigureCallback, &sensor_model_, _1, _2));
00108 
00109   Reset();
00110 
00111   // connect Update function
00112   updateTimer.setUpdateRate(10.0);
00113   updateTimer.Load(world, _sdf);
00114   updateConnection = updateTimer.Connect(boost::bind(&GazeboRosSonar::Update, this));
00115 
00116   // activate RaySensor
00117   sensor_->SetActive(true);
00118 }
00119 
00120 void GazeboRosSonar::Reset()
00121 {
00122   updateTimer.Reset();
00123   sensor_model_.reset();
00124 }
00125 
00127 // Update the controller
00128 void GazeboRosSonar::Update()
00129 {
00130   common::Time sim_time = world->GetSimTime();
00131   double dt = updateTimer.getTimeSinceLastUpdate().Double();
00132 
00133   // activate RaySensor if it is not yet active
00134   if (!sensor_->IsActive()) sensor_->SetActive(true);
00135 
00136   range_.header.stamp.sec  = (world->GetSimTime()).sec;
00137   range_.header.stamp.nsec = (world->GetSimTime()).nsec;
00138 
00139   // find ray with minimal range
00140   range_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max();
00141   int num_ranges = sensor_->GetLaserShape()->GetSampleCount() * sensor_->GetLaserShape()->GetVerticalSampleCount();
00142   for(int i = 0; i < num_ranges; ++i) {
00143     double ray = sensor_->GetLaserShape()->GetRange(i);
00144     if (ray < range_.range) range_.range = ray;
00145   }
00146 
00147   // add Gaussian noise (and limit to min/max range)
00148   if (range_.range < range_.max_range) {
00149     range_.range = sensor_model_(range_.range, dt);
00150     if (range_.range < range_.min_range) range_.range = range_.min_range;
00151     if (range_.range > range_.max_range) range_.range = range_.max_range;
00152   }
00153 
00154   publisher_.publish(range_);
00155 }
00156 
00157 // Register this plugin with the simulator
00158 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosSonar)
00159 
00160 } // namespace gazebo


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Aug 26 2015 11:44:35