functions.h
Go to the documentation of this file.
1 #ifndef functions_H
2 #define functions_H
3 #include "ros/ros.h"
4 #include <vector>
5 #include <stdlib.h>
6 #include <time.h>
7 #include <math.h>
8 #include "nav_msgs/OccupancyGrid.h"
9 #include "geometry_msgs/Point.h"
10 #include "visualization_msgs/Marker.h"
11 
12 // rdm class, for gentaring random flot numbers
13 class rdm{
14 int i;
15 public:
16 rdm();
17 float randomize();
18 };
19 
20 
21 //Norm function prototype
22 float Norm( std::vector<float> , std::vector<float> );
23 
24 //sign function prototype
25 float sign(float );
26 
27 //Nearest function prototype
28 std::vector<float> Nearest( std::vector< std::vector<float> > , std::vector<float> );
29 
30 //Steer function prototype
31 std::vector<float> Steer( std::vector<float>, std::vector<float>, float );
32 
33 //gridValue function prototype
34 int gridValue(nav_msgs::OccupancyGrid &,std::vector<float>);
35 
36 //ObstacleFree function prototype
37 char ObstacleFree(std::vector<float> , std::vector<float> & , nav_msgs::OccupancyGrid);
38 #endif
int i
Definition: functions.h:14
int gridValue(nav_msgs::OccupancyGrid &, std::vector< float >)
Definition: functions.cpp:77
std::vector< float > Steer(std::vector< float >, std::vector< float >, float)
Definition: functions.cpp:47
char ObstacleFree(std::vector< float >, std::vector< float > &, nav_msgs::OccupancyGrid)
Definition: functions.cpp:99
Definition: functions.h:13
float Norm(std::vector< float >, std::vector< float >)
Definition: functions.cpp:11
std::vector< float > Nearest(std::vector< std::vector< float > >, std::vector< float >)
Definition: functions.cpp:26
float randomize()
Definition: functions.cpp:6
float sign(float)
Definition: functions.cpp:18
rdm()
Definition: functions.cpp:5


rrt_exploration
Author(s): Hassan Umari
autogenerated on Mon Jun 10 2019 14:57:44