uos_freespace.h
Go to the documentation of this file.
00001 /*
00002  * uos_freespace
00003  * Author: Marat "Peter" Purnyn
00004  * Created 11/8/2015 (based on earlier work uos-freespace.cc)
00005  */
00006 #include <ros/ros.h>
00007 #include <sensor_msgs/LaserScan.h>
00008 #include "tf/transform_listener.h"
00009 #include <string>
00010 
00011 class FreeSpace {
00012         public:
00013                         FreeSpace();
00014         private:
00015                 //variables
00016                         double max_vel_x_, max_rotational_vel_; //max velocity of robot
00017                         double turn_omega_; //this is used to keep track of the turning angle of the robot when turn_state_ = 1;
00018                         int turn_state_;        //if robot gets too close to an object in front, it switches to turn mode
00019                                                                 //it keeps turning until there is no more obstacle and switches out of turn mode.
00020                         int scanner_orientation_; //0 for initial, 1 for right side up, -1 for upside-down laserscanner
00021                         std::string tf_prefix_; // optional tf_prefix
00022                 //node
00023                         ros::NodeHandle nh_;
00024                         ros::NodeHandle private_nh_;
00025                 //publishers
00026                         ros::Publisher vel_pub_;
00027                 //subscribers
00028                         ros::Subscriber laser_sub_;
00029                 //others
00030                         tf::TransformListener tf_;
00031                         
00032                 //functions
00033                         void autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan);
00034                         double calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan);
00035                         int isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan);
00036                         int checkRange(
00037                                 const sensor_msgs::LaserScan::ConstPtr &laserscan, 
00038                                 double xregion, double yregion,
00039                                 int *indexToObstacle, 
00040                                 double *distanceToObstacle);    
00041 };


uos_freespace
Author(s): Jochen Sprickerhof
autogenerated on Sat Jun 8 2019 19:40:51