LaserScanner.h
Go to the documentation of this file.
00001 #include <stdio.h>
00002 #include <stdlib.h>
00003 #include <unistd.h>
00004 #include <string.h>
00005 #include <sys/types.h>
00006 #include <sys/socket.h>
00007 #include <netinet/in.h>
00008 #include <netdb.h> 
00009 #include <string>
00010 //include ros libraries
00011 #include <ros/ros.h>
00012 #include <geometry_msgs/Twist.h>
00013 #include "sensor_msgs/LaserScan.h"
00014 #include "sensor_msgs/PointCloud2.h"
00015 #include <nav_msgs/Odometry.h>
00016 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00017 #include <tf/transform_datatypes.h>
00018 #include <tf/transform_listener.h>
00019 #include <nav_msgs/OccupancyGrid.h>
00020 #include <move_base_msgs/MoveBaseAction.h>
00021 #include <actionlib/client/simple_action_client.h>
00022 #include <kobuki_msgs/BumperEvent.h> 
00023 #include <kobuki_msgs/CliffEvent.h> 
00024 #include <kobuki_msgs/WheelDropEvent.h> 
00025 #include "../utils/utility_lib.h"
00026 using std::string;
00027 
00028 #ifndef LASERSCAN_H
00029 #define LASERSCAN_H
00030 
00033 class LaserScanner {
00034   
00035 public:
00036   
00041   static double Index2Angle(sensor_msgs::LaserScan laser_scan_msg, int index);
00042   static int Angle2Index(sensor_msgs::LaserScan laser_scan_msg, double angle);
00043 
00044         static int getIndexOfMaximumRange(sensor_msgs::LaserScan & LaserScanMsg);
00045   static int getIndexOfMinimumRange(sensor_msgs::LaserScan & LaserScanMsg);
00046   
00047   static double getRelativeAngleOfMaximumRange(sensor_msgs::LaserScan & msg);
00048   static double getRelativeAngleOfMinimumRange(sensor_msgs::LaserScan & LaserScanMsg);
00049   static void printLaserScanRanges(sensor_msgs::LaserScan::ConstPtr LaserScanMsg);
00050   static void printLaserScanRanges(sensor_msgs::LaserScan LaserScanMsg);
00051   
00052   static double getAverageRange (sensor_msgs::LaserScan & laser_scan_msg, int start_index, int end_index);
00053   static double getAverageRangeLeft(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00054   static double getAverageRangeRight(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00055   static double getAverageRangeStraight(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00056   
00057   static double getMaximumRange(sensor_msgs::LaserScan & msg);
00058   static double getFrontRange(sensor_msgs::LaserScan & msg);
00059   static double getMinimumRange(sensor_msgs::LaserScan & msg);
00060   
00061   static double getMinimumRange (sensor_msgs::LaserScan & laser_scan_msg, int start_index, int end_index);
00062   static double getMinimumRangeLeft(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00063   static double getMinimumRangeRight(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00064   
00065   static double getMaximumRange (sensor_msgs::LaserScan & laser_scan_msg, int start_index, int end_index);
00066   static double getMaximumRangeLeft(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00067   static double getMaximumRangeRight(sensor_msgs::LaserScan & laser_scan_msg, double degree);
00068   
00069   static bool isObstacleTooClose(sensor_msgs::LaserScan & LaserMsg, int start_index, int end_index, double DistanceThreshold);
00070   
00071 //private:
00072   
00073 };
00074 
00075 #endif


gapter
Author(s):
autogenerated on Thu Jun 6 2019 22:05:13