ProximityRayPlugin.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2012-2016 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 #include <functional>
00018 #include <cstdio>
00019 
00020 #include <boost/algorithm/string/replace.hpp>
00021 #include <gazebo/physics/physics.hh>
00022 #include <gazebo/transport/Node.hh>
00023 #include <gazebo/transport/Publisher.hh>
00024 #include "ProximityRayPlugin.hh"
00025 
00026 using namespace gazebo;
00027 
00028 // Register this plugin with the simulator
00029 GZ_REGISTER_SENSOR_PLUGIN(ProximityRayPlugin)
00030 
00031 
00032 ProximityRayPlugin::ProximityRayPlugin()
00033 {
00034 }
00035 
00037 ProximityRayPlugin::~ProximityRayPlugin()
00038 {
00039     this->newLaserScansConnection.reset();
00040 
00041     this->parentSensor.reset();
00042     this->world.reset();
00043 }
00044 
00046 std::string ProximityRayPlugin::Topic(std::string topicName) const
00047 {
00048   std::string globalTopicName = "~/";
00049   globalTopicName += this->parentSensor->Name() + "/" + this->GetHandle() + "/" + topicName;
00050   boost::replace_all(globalTopicName, "::", "/");
00051 
00052   return globalTopicName;
00053 }
00054 
00056 void ProximityRayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00057 {
00058     // Get the name of the parent sensor
00059     this->parentSensor =
00060         std::dynamic_pointer_cast<sensors::RaySensor>(_parent);
00061 
00062     if (!this->parentSensor)
00063         gzthrow("ProximityRayPlugin requires a Ray Sensor as its parent");
00064 
00065     std::string worldName = this->parentSensor->WorldName();
00066     this->world = physics::get_world(worldName);
00067     this->node = transport::NodePtr(new transport::Node());
00068     this->node->Init(worldName);
00069 
00070     if (_sdf->HasElement("time_delay"))
00071     {
00072       double time_delay = _sdf->Get<double>("time_delay");
00073       this->parentSensor->SetUpdateRate(1.0/time_delay);
00074       gzdbg << "Setting update rate of parent sensor to " << 1.0/time_delay << " Hz\n";
00075     }
00076     else {
00077       gzdbg << "Using update rate of parent sensor: " << this->parentSensor->UpdateRate() << " Hz\n";
00078     }
00079 
00080     if (_sdf->HasElement("output_state_topic"))
00081     {
00082         this->stateTopic = _sdf->Get<std::string>("output_state_topic");
00083     }
00084     else {
00085         this->stateTopic = this->Topic("sensor_state");
00086     }
00087 
00088     this->statePub =
00089         this->node->Advertise<msgs::Header>(this->stateTopic, 50);
00090 
00091     if (_sdf->HasElement("output_change_topic"))
00092     {
00093         this->stateChangeTopic = _sdf->Get<std::string>("output_change_topic");
00094     }
00095     else {
00096         this->stateChangeTopic = this->Topic("state_change");
00097     }
00098 
00099     this->stateChangePub =
00100         this->node->Advertise<msgs::Header>(this->stateChangeTopic, 50);
00101 
00102     // TODO: override sensor's range values
00103     /*
00104     if (_sdf->HasElement("sensing_range_min"))
00105     {
00106       this->sensingRangeMin = _sdf->Get<double>("sensing_range_min");
00107     }
00108     else {
00109       this->sensingRangeMin = this->parentSensor->RangeMin();
00110     }
00111     gzdbg << "Using mininimum sensing range of: " << this->sensingRangeMin << " m\n";
00112 
00113     if (_sdf->HasElement("sensing_range_max"))
00114     {
00115       this->sensingRangeMax = _sdf->Get<double>("sensing_range_max");
00116     }
00117     else {
00118       this->sensingRangeMax = this->parentSensor->RangeMax();
00119     }
00120     gzdbg << "Using maximum sensing range of: " << this->sensingRangeMax << " m\n";
00121     */
00122 
00123     this->useLinkFrame = true;
00124     if (_sdf->HasElement("use_link_frame"))
00125     {
00126       this->useLinkFrame = _sdf->Get<bool>("use_link_frame");
00127     }
00128     if (this->useLinkFrame)
00129     {
00130       std::string linkName = this->parentSensor->ParentName();
00131       this->link = boost::dynamic_pointer_cast<physics::Link>(this->world->GetEntity(linkName));
00132     }
00133 
00134     this->objectDetected = false;
00135     this->newLaserScansConnection =
00136         this->parentSensor->LaserShape()->ConnectNewLaserScans(
00137             std::bind(&ProximityRayPlugin::OnNewLaserScans, this));
00138 }
00139 
00141 void ProximityRayPlugin::OnNewLaserScans()
00142 {
00143     bool stateChanged = this->ProcessScan();
00144 
00145     // Fill message
00146     std::lock_guard<std::mutex> lock(this->mutex);
00147     msgs::Set(this->stateMsg.mutable_stamp(), this->world->GetSimTime());
00148     this->stateMsg.set_index(this->objectDetected);
00149 
00150     // Publish sensor state message
00151     if (this->statePub && this->statePub->HasConnections()) {
00152         this->statePub->Publish(this->stateMsg);
00153     }
00154 
00155     if (stateChanged)
00156     {
00157         // Publish state state change message
00158         if (this->stateChangePub && this->stateChangePub->HasConnections()) {
00159             this->stateChangePub->Publish(this->stateMsg);
00160         }
00161     }
00162 }
00163 
00165 bool ProximityRayPlugin::ProcessScan()
00166 {
00167     bool stateChanged = false;
00168     // Prevent new scans from arriving while we're processing this one
00169     this->parentSensor->SetActive(false);
00170 
00171     this->sensingRangeMax = this->parentSensor->RangeMax();
00172     this->sensingRangeMin = this->parentSensor->RangeMin();
00173     std::vector<double> ranges;
00174     this->parentSensor->Ranges(ranges);
00175 
00176     bool objectDetected = false;
00177 
00178     for (unsigned int i = 0; i<ranges.size(); i++){
00179         double range = ranges[i];
00180         // TODO: determine detections in cylindrical shape not spherical
00181         if (range < this->sensingRangeMax and range > this->sensingRangeMin) {
00182             objectDetected = true;
00183             break;
00184         }
00185     }
00186 
00187     if (objectDetected) {
00188         if (!this->objectDetected) {
00189           gzdbg << "Object detected\n";
00190           stateChanged = true;
00191         }
00192         this->objectDetected = true;
00193     }
00194     else
00195     {
00196         if (this->objectDetected) {
00197           gzdbg << "Object no longer detected\n";
00198           stateChanged = true;
00199         }
00200         this->objectDetected = false;
00201     }
00202 
00203     if (this->useLinkFrame)
00204     {
00205       // TODO: deal with sensors oriented differently
00206       auto sensorPose = this->parentSensor->Pose();
00207       this->sensingRangeMin += sensorPose.Pos().X();
00208       this->sensingRangeMax += sensorPose.Pos().X();
00209     }
00210 
00211     this->parentSensor->SetActive(true); // this seems to happen automatically, not sure if a bug
00212 
00213     return stateChanged;
00214 }


osrf_gear
Author(s):
autogenerated on Mon Sep 5 2016 03:41:33