30 #include <gazebo/physics/World.hh> 
   31 #include <gazebo/physics/HingeJoint.hh> 
   32 #include <gazebo/sensors/Sensor.hh> 
   34 #include <sdf/Param.hh> 
   35 #include <gazebo/common/Exception.hh> 
   36 #include <gazebo/sensors/RaySensor.hh> 
   37 #include <gazebo/sensors/SensorTypes.hh> 
   38 #include <gazebo/transport/Node.hh> 
   40 #ifdef ENABLE_PROFILER 
   41 #include <ignition/common/Profiler.hh> 
   44 #include <geometry_msgs/Point32.h> 
   45 #include <sensor_msgs/ChannelFloat32.h> 
   49 #define EPSILON_DIFF 0.000001 
   54 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBlockLaser)
 
   81   RayPlugin::Load(_parent, _sdf);
 
   87   std::string worldName = _parent->WorldName();
 
   88   this->
world_ = physics::get_world(worldName);
 
   90 #if GAZEBO_MAJOR_VERSION >= 8 
   96   this->
node_ = transport::NodePtr(
new transport::Node());
 
   97   this->
node_->Init(worldName);
 
  103     gzthrow(
"GazeboRosBlockLaser controller requires a Ray Sensor as its parent");
 
  106   if (_sdf->HasElement(
"robotNamespace"))
 
  107     this->
robot_namespace_ = _sdf->GetElement(
"robotNamespace")->Get<std::string>() + 
"/";
 
  109   if (!_sdf->HasElement(
"frameName"))
 
  111     ROS_INFO_NAMED(
"block_laser", 
"Block laser plugin missing <frameName>, defaults to /world");
 
  115     this->
frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
 
  117   if (!_sdf->HasElement(
"topicName"))
 
  119     ROS_INFO_NAMED(
"block_laser", 
"Block laser plugin missing <topicName>, defaults to /world");
 
  123     this->
topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
 
  125   if (!_sdf->HasElement(
"gaussianNoise"))
 
  127     ROS_INFO_NAMED(
"block_laser", 
"Block laser plugin missing <gaussianNoise>, defaults to 0.0");
 
  131     this->
gaussian_noise_ = _sdf->GetElement(
"gaussianNoise")->Get<
double>();
 
  133   if (!_sdf->HasElement(
"hokuyoMinIntensity"))
 
  135     ROS_INFO_NAMED(
"block_laser", 
"Block laser plugin missing <hokuyoMinIntensity>, defaults to 101");
 
  143   if (!_sdf->HasElement(
"updateRate"))
 
  145     ROS_INFO_NAMED(
"block_laser", 
"Block laser plugin missing <updateRate>, defaults to 0");
 
  149     this->
update_rate_ = _sdf->GetElement(
"updateRate")->Get<
double>();
 
  158     ROS_FATAL_STREAM_NAMED(
"block_laser", 
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 
  159       << 
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
 
  173   this->
cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
 
  216 #ifdef ENABLE_PROFILER 
  217   IGN_PROFILE(
"GazeboRosBlockLaser::OnNewLaserScans");
 
  221     common::Time sensor_update_time = this->
parent_sensor_->LastUpdateTime();
 
  224         ROS_WARN_NAMED(
"block_laser", 
"Negative sensor update time difference detected.");
 
  230 #ifdef ENABLE_PROFILER 
  231       IGN_PROFILE_BEGIN(
"PutLaserData");
 
  234 #ifdef ENABLE_PROFILER 
  242     ROS_INFO_NAMED(
"block_laser", 
"gazebo_ros_block_laser topic name not set");
 
  254   double r1, r2, r3, r4, r; 
 
  272   double yDiff = maxAngle.Radian() - minAngle.Radian();
 
  273   double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
 
  280   this->
cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
 
  287   boost::mutex::scoped_lock sclock(this->
lock);
 
  290   this->
cloud_msg_.header.stamp.sec = _updateTime.sec;
 
  291   this->
cloud_msg_.header.stamp.nsec = _updateTime.nsec;
 
  293   for (j = 0; j<verticalRangeCount; j++)
 
  296     vb = (verticalRangeCount == 1) ? 0 : (
double) j * (verticalRayCount - 1) / (verticalRangeCount - 1);
 
  297     vja = (int) floor(vb);
 
  298     vjb = std::min(vja + 1, verticalRayCount - 1);
 
  301     assert(vja >= 0 && vja < verticalRayCount);
 
  302     assert(vjb >= 0 && vjb < verticalRayCount);
 
  304     for (i = 0; i<rangeCount; i++)
 
  307       hb = (rangeCount == 1)? 0 : (
double) i * (rayCount - 1) / (rangeCount - 1);
 
  308       hja = (int) floor(hb);
 
  309       hjb = std::min(hja + 1, rayCount - 1);
 
  312       assert(hja >= 0 && hja < rayCount);
 
  313       assert(hjb >= 0 && hjb < rayCount);
 
  316       j1 = hja + vja * rayCount;
 
  317       j2 = hjb + vja * rayCount;
 
  318       j3 = hja + vjb * rayCount;
 
  319       j4 = hjb + vjb * rayCount;
 
  328       r = (1-vb)*((1 - hb) * r1 + hb * r2)
 
  329          +   vb *((1 - hb) * r3 + hb * r4);
 
  334         r = -std::numeric_limits<double>::infinity();
 
  336       else if ( r > maxRange)
 
  338         r = std::numeric_limits<double>::infinity();
 
  354       double yAngle = 0.5*(hja+hjb) * yDiff / (rayCount -1) + minAngle.Radian();
 
  355       double pAngle = 0.5*(vja+vjb) * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
 
  362       geometry_msgs::Point32 point;
 
  364       point.x = r * cos(pAngle) * cos(yAngle);
 
  365       point.y = r * cos(pAngle) * sin(yAngle);
 
  366       point.z = r * sin(pAngle);
 
  396   double U = (double)rand()/(double)RAND_MAX; 
 
  397   double V = (double)rand()/(double)RAND_MAX; 
 
  398   double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
 
  411   static const double timeout = 0.01;
 
  421   this->
sim_time_  = msgs::Convert( _msg->sim_time() );
 
  423   ignition::math::Pose3d pose;
 
  424   pose.Pos().X() = 0.5*sin(0.01*this->
sim_time_.Double());
 
  425   gzdbg << 
"plugin simTime [" << this->
sim_time_.Double() << 
"] update pose [" << pose.Pos().X() << 
"]\n";