uos_freespace.h
Go to the documentation of this file.
1 /*
2  * uos_freespace
3  * Author: Marat "Peter" Purnyn
4  * Created 11/8/2015 (based on earlier work uos-freespace.cc)
5  */
6 #include <ros/ros.h>
7 #include <sensor_msgs/LaserScan.h>
9 #include <string>
10 
11 class FreeSpace {
12  public:
13  FreeSpace();
14  private:
15  //variables
16  double max_vel_x_, max_rotational_vel_; //max velocity of robot
17  double turn_omega_; //this is used to keep track of the turning angle of the robot when turn_state_ = 1;
18  int turn_state_; //if robot gets too close to an object in front, it switches to turn mode
19  //it keeps turning until there is no more obstacle and switches out of turn mode.
20  int scanner_orientation_; //0 for initial, 1 for right side up, -1 for upside-down laserscanner
21  std::string tf_prefix_; // optional tf_prefix
22  //node
25  //publishers
27  //subscribers
29  //others
31 
32  //functions
33  void autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan);
34  double calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan);
35  int isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan);
36  int checkRange(
37  const sensor_msgs::LaserScan::ConstPtr &laserscan,
38  double xregion, double yregion,
39  int *indexToObstacle,
40  double *distanceToObstacle);
41 };
int isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan)
ros::NodeHandle private_nh_
Definition: uos_freespace.h:24
std::string tf_prefix_
Definition: uos_freespace.h:21
double turn_omega_
Definition: uos_freespace.h:17
ros::NodeHandle nh_
Definition: uos_freespace.h:23
int scanner_orientation_
Definition: uos_freespace.h:20
double max_rotational_vel_
Definition: uos_freespace.h:16
tf::TransformListener tf_
Definition: uos_freespace.h:30
ros::Subscriber laser_sub_
Definition: uos_freespace.h:28
double max_vel_x_
Definition: uos_freespace.h:16
void autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan)
int turn_state_
Definition: uos_freespace.h:18
ros::Publisher vel_pub_
Definition: uos_freespace.h:26
int checkRange(const sensor_msgs::LaserScan::ConstPtr &laserscan, double xregion, double yregion, int *indexToObstacle, double *distanceToObstacle)
double calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan)


uos_freespace
Author(s): Jochen Sprickerhof
autogenerated on Mon Jun 10 2019 15:49:30