gazebo_ros_ir_sensor.cpp
Go to the documentation of this file.
00001 #include <algorithm>
00002 #include <string>
00003 #include <assert.h>
00004 
00005 #include <gazebo/physics/World.hh>
00006 #include <gazebo/physics/HingeJoint.hh>
00007 #include <gazebo/sensors/Sensor.hh>
00008 #include <gazebo/common/Exception.hh>
00009 #include <gazebo/sensors/RaySensor.hh>
00010 #include <gazebo/sensors/SensorTypes.hh>
00011 #include <gazebo/transport/transport.hh>
00012 
00013 #include <sdf/sdf.hh>
00014 #include <sdf/Param.hh>
00015 
00016 #include <tf/tf.h>
00017 #include <tf/transform_listener.h>
00018 
00019 #include "gazebo_ros_ir_sensor.h"
00020 
00021 
00022 namespace gazebo {
00023   // Register this plugin with the simulator
00024   GZ_REGISTER_SENSOR_PLUGIN(GazeboRosIrSensor)
00025 
00026   // Constructor
00027   GazeboRosIrSensor::GazeboRosIrSensor() {
00028     this->seed = 0;
00029   }
00030 
00031   // Destructor
00032   GazeboRosIrSensor::~GazeboRosIrSensor() {
00033     this->rosnode_->shutdown();
00034     delete this->rosnode_;
00035   }
00036 
00037   // Load the controller
00038   void GazeboRosIrSensor::Load(sensors::SensorPtr _parent,
00039                                sdf::ElementPtr _sdf) {
00040     // Load plugin
00041     RayPlugin::Load(_parent, this->sdf);
00042 
00043     // Get the world name.
00044     # if GAZEBO_MAJOR_VERSION >= 7
00045       std::string worldName = _parent->WorldName();
00046     # else
00047       std::string worldName = _parent->GetWorldName();
00048     #endif
00049 
00050     this->world_ = physics::get_world(worldName);
00051 
00052     // Save pointers
00053     this->sdf = _sdf;
00054 
00055     GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
00056     this->parent_ray_sensor_ =
00057       dynamic_pointer_cast<sensors::RaySensor>(_parent);
00058 
00059     if (!this->parent_ray_sensor_)
00060       gzthrow("GazeboRosIrSensor controller requires a Ray Sensor as its parent");
00061 
00062     this->robot_namespace_ = GetRobotNamespace(_parent, _sdf, "IR_Sensor");
00063 
00064     if (!this->sdf->HasElement("frameName")) {
00065       ROS_INFO_NAMED(
00066         "ir_sensor",
00067         "IR Sensor plugin missing <frameName>, defaults to world");
00068       this->frame_name_ = "/world";
00069 
00070     } else {
00071       this->frame_name_ = this->sdf->Get<std::string>("frameName");
00072 
00073     }
00074 
00075     if (!this->sdf->HasElement("topicName")) {
00076       ROS_INFO_NAMED(
00077         "ir_sensor",
00078         "IR Sensor plugin missing <topicName>, defaults to /world");
00079       this->topic_name_ = "/world";
00080 
00081     } else {
00082       this->topic_name_ = this->sdf->Get<std::string>("topicName");
00083 
00084     }
00085 
00086     this->ir_sensor_connect_count_ = 0;
00087 
00088     // Make sure the ROS node for Gazebo has already been initialized.
00089     if (!ros::isInitialized()) {
00090       ROS_FATAL_STREAM_NAMED("ir_sensor", "A ROS node for Gazebo has not been initialized, unable to load plugin. " << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00091       return;
00092     }
00093 
00094     ROS_INFO_NAMED(
00095       "ir_sensor",
00096       "Starting IR Sensor Plugin (ns = %s)",
00097       this->robot_namespace_.c_str());
00098 
00099     // ros callback queue for processing subscription
00100     this->deferred_load_thread_ = boost::thread(
00101       boost::bind(&GazeboRosIrSensor::LoadThread, this));
00102   }
00103 
00104   // Load the controller
00105   void GazeboRosIrSensor::LoadThread() {
00106     this->gazebo_node_ = gazebo::transport::NodePtr(
00107       new gazebo::transport::Node());
00108     this->gazebo_node_->Init(this->world_name_);
00109 
00110     this->pmq.startServiceThread();
00111 
00112     this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00113 
00114     this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
00115     if (this->tf_prefix_.empty()) {
00116       this->tf_prefix_ = this->robot_namespace_;
00117       boost::trim_right_if(this->tf_prefix_, boost::is_any_of("/"));
00118 
00119     }
00120 
00121     ROS_INFO_NAMED(
00122       "ir_sensor",
00123       "IR Sensor Plugin (ns = %s) <tf_prefix>, set to \"%s\"",
00124       this->robot_namespace_.c_str(),
00125       this->tf_prefix_.c_str());
00126 
00127     // Resolve tf prefix
00128     this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
00129 
00130     if (this->topic_name_ != "") {
00131       ros::AdvertiseOptions ao =
00132         ros::AdvertiseOptions::create<std_msgs::Float32>(
00133           this->topic_name_,
00134           1,
00135           boost::bind(&GazeboRosIrSensor::IrSensorConnect, this),
00136           boost::bind(&GazeboRosIrSensor::IrSensorDisconnect, this),
00137           ros::VoidPtr(),
00138           NULL);
00139       this->pub_ = this->rosnode_->advertise(ao);
00140       this->pub_queue_ = this->pmq.addPub<std_msgs::Float32>();
00141     }
00142 
00143     // Initialize the controller
00144 
00145     // Sensor generation off by default
00146     this->parent_ray_sensor_->SetActive(false);
00147 
00148   }
00149 
00150   // Increment Count
00151   void GazeboRosIrSensor::IrSensorConnect() {
00152     this->ir_sensor_connect_count_++;
00153     if (this->ir_sensor_connect_count_ == 1) {
00154       # if GAZEBO_MAJOR_VERSION >= 7
00155         this->ir_sensor_scan_sub_ =
00156           this->gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(),
00157                                         &GazeboRosIrSensor::OnScan, this);
00158       # else
00159         this->ir_sensor_scan_sub_ =
00160           this->gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(),
00161                                         &GazeboRosIrSensor::OnScan, this);
00162       # endif
00163     }
00164   }
00165 
00166   // Decrement Count
00167   void GazeboRosIrSensor::IrSensorDisconnect() {
00168     this->ir_sensor_connect_count_--;
00169     if (this->ir_sensor_connect_count_ == 0) {
00170       this->ir_sensor_scan_sub_.reset();
00171     }
00172   }
00173 
00174   /**************************************************************
00175    * Convert New Gazebo Message to ROS message and publish it
00176    *
00177    * From my research with the values returned in scan(). The maximum and
00178    * minimum limits for the ray specified in the robot's XML file (look at
00179    * the ir_sensor.urdf.xacro file within this repository for reference) are
00180    * the values returned by `_msg->scan().ranges()`.
00181    *
00182    * 720 values are returned by `_msg->scan().ranges()`, however, they all seem
00183    * to be the same information. Either .3 if nothing is in front of the sensor
00184    * or lesser values pertaining to the distance from the sensor. If a box is
00185    * in front of the sensor 0.10 m from the pheeno, ALL the values of
00186    * `_msg->scan().ranges()` will read about 0.10 m.
00187    *
00188    * Since my inquiring lead to this conclusion, I will only use the first
00189    * value coming from `_msg->scan().ranges(0)` and then multiplying it by
00190    * 100 to return the values in cm instead of m.
00191    **************************************************************/
00192   void GazeboRosIrSensor::OnScan(ConstLaserScanStampedPtr &_msg) {
00193     // Declare ROS Message
00194     std_msgs::Float32 ir_sensor_msg;
00195 
00196     // Set the sensor value.
00197     ir_sensor_msg.data = (float)_msg->scan().ranges(0) * 100.0;
00198 
00199     // Publish message.
00200     this->pub_queue_->push(ir_sensor_msg, this->pub_);
00201   }
00202 }


pheeno_ros_sim
Author(s): Zahi Kakish
autogenerated on Thu Jun 6 2019 19:59:41