ncd_parser.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Ivan Dryanovski, William Morris
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the CCNY Robotics Lab nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef NCD_PARSER_NCD_PARSER
31 #define NCD_PARSER_NCD_PARSER
32 
33 #include <iostream>
34 #include <fstream>
35 
36 #include <ros/ros.h>
38 #include <sensor_msgs/LaserScan.h>
39 
40 const double DEG_TO_RAD = 3.14159 / 180.0;
41 
42 const double RANGE_MIN = 0.20;
43 const double RANGE_MAX = 50.0;
44 
45 const std::string worldFrame_ = "map";
46 const std::string odomFrame_ = "odom";
47 const std::string leftLaserFrame_ = "laser_left";
48 const std::string rightLaserFrame_ = "laser_right";
49 
50 class NCDParser
51 {
52  private:
53 
54  char* filename_;
55  double rate_;
56  double start_, end_;
57  double lastTime_;
58 
61 
63 
67 
68  void publishLaserMessage(const std::vector<std::string>& tokens,
69  const std::string& laserFrame,
70  const ros::Publisher& publisher);
71 
72  void publishTfMessages(const std::vector<std::string>& tokens);
73 
74  void tokenize (const std::string& str,
75  std::vector <std::string> &tokens,
76  std::string sentinel);
77 
78  std::vector<float> extractArray(std::string s, std::string pattern);
79 
80  double extractValue(std::string s, std::string pattern);
81 
84 
85  public:
86 
87  NCDParser(char* filename);
88  virtual ~NCDParser();
89 
90  void launch();
91 };
92 
93 #endif
const double RANGE_MAX
Definition: ncd_parser.h:43
tf::TransformBroadcaster tfBroadcaster_
Definition: ncd_parser.h:62
const double DEG_TO_RAD
Definition: ncd_parser.h:40
const std::string odomFrame_
Definition: ncd_parser.h:46
char * filename_
Definition: ncd_parser.h:54
tf::Transform worldToOdom_
Definition: ncd_parser.h:64
double end_
Definition: ncd_parser.h:56
double extractValue(std::string s, std::string pattern)
Definition: ncd_parser.cpp:240
void launch()
Definition: ncd_parser.cpp:80
const std::string leftLaserFrame_
Definition: ncd_parser.h:47
ros::Publisher leftLaserPublisher_
Definition: ncd_parser.h:59
void publishLaserMessage(const std::vector< std::string > &tokens, const std::string &laserFrame, const ros::Publisher &publisher)
Definition: ncd_parser.cpp:145
void tokenize(const std::string &str, std::vector< std::string > &tokens, std::string sentinel)
Definition: ncd_parser.cpp:207
double start_
Definition: ncd_parser.h:56
std::vector< float > extractArray(std::string s, std::string pattern)
Definition: ncd_parser.cpp:223
virtual ~NCDParser()
Definition: ncd_parser.cpp:75
void createOdomToRightLaserTf()
Definition: ncd_parser.cpp:267
void createOdomToLeftLaserTf()
Definition: ncd_parser.cpp:249
const double RANGE_MIN
Definition: ncd_parser.h:42
tf::Transform odomToRightLaser_
Definition: ncd_parser.h:66
const std::string worldFrame_
Definition: ncd_parser.h:45
ros::Publisher rightLaserPublisher_
Definition: ncd_parser.h:60
void publishTfMessages(const std::vector< std::string > &tokens)
Definition: ncd_parser.cpp:169
NCDParser(char *filename)
Definition: ncd_parser.cpp:47
double lastTime_
Definition: ncd_parser.h:57
double rate_
Definition: ncd_parser.h:55
tf::Transform odomToLeftLaser_
Definition: ncd_parser.h:65
const std::string rightLaserFrame_
Definition: ncd_parser.h:48


ncd_parser
Author(s): Ivan Dryanovski
autogenerated on Mon Jun 10 2019 15:08:47