Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
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 }