laser.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002    STDR Simulator - Simple Two DImensional Robot Simulator
00003    Copyright (C) 2013 STDR Simulator
00004    This program is free software; you can redistribute it and/or modify
00005    it under the terms of the GNU General Public License as published by
00006    the Free Software Foundation; either version 3 of the License, or
00007    (at your option) any later version.
00008    This program is distributed in the hope that it will be useful,
00009    but WITHOUT ANY WARRANTY; without even the implied warranty of
00010    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011    GNU General Public License for more details.
00012    You should have received a copy of the GNU General Public License
00013    along with this program; if not, write to the Free Software Foundation,
00014    Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301  USA
00015    
00016    Authors : 
00017    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com 
00020 ******************************************************************************/
00021 
00022 #include <stdr_robot/sensors/laser.h>
00023 
00024 namespace stdr_robot {
00025 
00034   Laser::Laser(const nav_msgs::OccupancyGrid& map,
00035       const stdr_msgs::LaserSensorMsg& msg, 
00036       const std::string& name,
00037       ros::NodeHandle& n)
00038   : 
00039     Sensor(map, name, n, msg.pose, msg.frame_id, msg.frequency)
00040   {
00041     _description = msg;
00042 
00043     _publisher = n.advertise<sensor_msgs::LaserScan>
00044       ( _namespace + "/" + msg.frame_id, 1 );
00045   }
00046 
00051   void Laser::updateSensorCallback() 
00052   {
00053     float angle;
00054     int distance;
00055     int xMap, yMap;
00056     sensor_msgs::LaserScan _laserScan;
00057 
00058     _laserScan.angle_min = _description.minAngle;
00059     _laserScan.angle_max = _description.maxAngle;
00060     _laserScan.range_max = _description.maxRange;
00061     _laserScan.range_min = _description.minRange;
00062     _laserScan.angle_increment = 
00063       ( _description.maxAngle - _description.minAngle ) / _description.numRays;
00064 
00065 
00066     if ( _map.info.height == 0 || _map.info.width == 0 ) 
00067     {
00068       ROS_DEBUG("Outside limits\n");
00069       return;
00070     }
00071     for ( int laserScanIter = 0; laserScanIter < _description.numRays; 
00072       laserScanIter++ )
00073     {
00074 
00075       angle = tf::getYaw(_sensorTransform.getRotation()) + 
00076         _description.minAngle + laserScanIter * 
00077           ( _description.maxAngle - _description.minAngle ) 
00078             / _description.numRays;
00079       
00080       distance = 1;
00081 
00082       while ( distance <= _description.maxRange / _map.info.resolution )
00083       {
00084         xMap = _sensorTransform.getOrigin().x() / _map.info.resolution + 
00085           cos( angle ) * distance;
00086         
00087         yMap = _sensorTransform.getOrigin().y() / _map.info.resolution + 
00088           sin( angle ) * distance;
00089         
00090         if (yMap * _map.info.width + xMap > _map.info.height*_map.info.width)
00091           return;
00092         
00093         if ( _map.data[ yMap * _map.info.width + xMap ] > 70 )
00094         {
00095           break;
00096         }
00097         
00098         distance ++;
00099       }
00100 
00101       if ( distance * _map.info.resolution > _description.maxRange )
00102         _laserScan.ranges.push_back( std::numeric_limits<float>::infinity() );
00103       else if ( distance * _map.info.resolution < _description.minRange )
00104         _laserScan.ranges.push_back(- std::numeric_limits<float>::infinity() );
00105       else
00106         _laserScan.ranges.push_back( distance * _map.info.resolution );
00107     }
00108     
00109     _laserScan.header.stamp = ros::Time::now();
00110     _laserScan.header.frame_id = _namespace + "_" + _description.frame_id;
00111     _publisher.publish( _laserScan );
00112   }
00113 
00114 }  // namespace stdr_robot


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:25