obstacle_avoidance.h
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 #ifndef STDR_OBSTACLE_AVOIDANCE_SAMPLE
22 #define STDR_OBSTACLE_AVOIDANCE_SAMPLE
23 
24 #include <iostream>
25 #include <cstdlib>
26 #include <cmath>
27 
28 #include <ros/package.h>
29 #include "ros/ros.h"
30 
31 #include <stdr_msgs/RobotIndexedVectorMsg.h>
32 
33 #include <geometry_msgs/Pose2D.h>
34 #include <geometry_msgs/Point.h>
35 #include <geometry_msgs/Twist.h>
36 #include <sensor_msgs/LaserScan.h>
37 #include <sensor_msgs/Range.h>
38 
43 namespace stdr_samples
44 {
50  {
51  private:
52 
54  sensor_msgs::LaserScan scan_;
55 
58 
61 
63  std::string laser_topic_;
64 
66  std::string speeds_topic_;
67 
70 
71  public:
72 
79  ObstacleAvoidance(int argc,char **argv);
80 
85  ~ObstacleAvoidance(void);
86 
92  void callback(const sensor_msgs::LaserScan& msg);
93 
94  };
95 }
96 
97 #endif
ros::NodeHandle n_
The laser topic.
std::string laser_topic_
The speeds topic.
ros::Subscriber subscriber_
The ROS node handle.
sensor_msgs::LaserScan scan_
< The ros laser scan msg
void callback(const sensor_msgs::LaserScan &msg)
Callback for the ros laser message.
ObstacleAvoidance(int argc, char **argv)
Default contructor.
Performs obstacle avoidance to a single robot.
std::string speeds_topic_
The twist publisher.
~ObstacleAvoidance(void)
Default destructor.
The main namespace for STDR Samples.


stdr_samples
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:03