extract_rosbag_signals.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020 PAL Robotics SL. All Rights Reserved
3  *
4  * Unauthorized copying of this file, via any medium is strictly prohibited,
5  * unless it was supplied under the terms of a license agreement or
6  * nondisclosure agreement with PAL Robotics SL. In this case it may not be
7  * copied or disclosed except in accordance with the terms of that agreement.
8  */
9 #ifndef EXTRACT_ROSBAG_SIGNALS_H
10 #define EXTRACT_ROSBAG_SIGNALS_H
11 
13 
14 namespace pal_statistics {
15 typedef std::pair<ros::Time, double> TimeData;
16 
17 /* This class extract the signals from a rosbag */
18 class DataSignals {
19 public:
20 
21  /* Constructor:
22  * - variables_names: name of the variables to be extracted from the rosbag
23  * - rosbag_path: rosbag location
24  * - topic_name: topic where to extract the variables. By default is /introspection_data. This topic must be splitted as /introspection_data/names, /introspection_data/values
25  */
26  DataSignals(const std::vector<std::string> &variables_names,
27  const std::string &rosbag_path,
28  const std::string &topic_name = "/introspection_data");
29  ~DataSignals();
30 
31  /* Receives the whole signal from a specific variable */
32  std::vector<TimeData> getDataSignal(const std::string &name) const;
33 
34  /* Receives the names of all the choosen variables in the constructor */
35  std::vector<std::string> getDataSignalNames() const;
36 
37  /* Receives the signals from the choosen variables in the constructor */
38  std::vector<std::vector<TimeData>> getDataValues() const;
39 
40  /* From the choosen signals returns the minimum size */
41  size_t getDataValuesMinSize() const;
42 
43  /* From the choosen signals returns the maximum size */
44  size_t getDataValuesMaxSize() const;
45 
46  /* Returns a map with the names of the variables and his coefficient in the list */
47  std::map<std::string, int> getIndexMap() const;
48 
49  /* Returns a screenshot from all the variables at a specific moment of time */
50  std::vector<TimeData> getDataValue(const ros::Duration &time) const;
51 
52  /* Returns a screenshot from all the variables at a specific coefficient */
53  std::vector<TimeData> getInstantDataValues(size_t coeff) const;
54 
55 private:
56  std::map<std::string, std::vector<TimeData>> data_;
57 };
58 } // namespace pal_statistics
59 
60 #endif // EXTRACT_ROSBAG_SIGNALS_H
pal_statistics::DataSignals::getInstantDataValues
std::vector< TimeData > getInstantDataValues(size_t coeff) const
Definition: extract_rosbag_signals.cpp:156
pal_statistics::DataSignals::getDataValuesMinSize
size_t getDataValuesMinSize() const
Definition: extract_rosbag_signals.cpp:115
pal_statistics::DataSignals::getIndexMap
std::map< std::string, int > getIndexMap() const
Definition: extract_rosbag_signals.cpp:146
pal_statistics::DataSignals::getDataSignal
std::vector< TimeData > getDataSignal(const std::string &name) const
Definition: extract_rosbag_signals.cpp:79
pal_statistics::DataSignals::~DataSignals
~DataSignals()
Definition: extract_rosbag_signals.cpp:76
pal_statistics::DataSignals::getDataValues
std::vector< std::vector< TimeData > > getDataValues() const
Definition: extract_rosbag_signals.cpp:98
pal_statistics::DataSignals
Definition: extract_rosbag_signals.h:18
pal_statistics::DataSignals::data_
std::map< std::string, std::vector< TimeData > > data_
Definition: extract_rosbag_signals.h:56
pal_statistics::DataSignals::getDataValuesMaxSize
size_t getDataValuesMaxSize() const
Definition: extract_rosbag_signals.cpp:106
pal_statistics::TimeData
std::pair< ros::Time, double > TimeData
Definition: extract_rosbag_signals.h:15
pal_statistics
Definition: extract_rosbag_signals.h:14
pal_statistics::DataSignals::DataSignals
DataSignals(const std::vector< std::string > &variables_names, const std::string &rosbag_path, const std::string &topic_name="/introspection_data")
Definition: extract_rosbag_signals.cpp:17
pal_statistics_utils.h
pal_statistics::DataSignals::getDataValue
std::vector< TimeData > getDataValue(const ros::Duration &time) const
Definition: extract_rosbag_signals.cpp:127
ros::Duration
pal_statistics::DataSignals::getDataSignalNames
std::vector< std::string > getDataSignalNames() const
Definition: extract_rosbag_signals.cpp:90


pal_statistics
Author(s):
autogenerated on Fri Aug 2 2024 08:29:35