Template Struct BagToFrames
Defined in File bag_to_frames.hpp
Struct Documentation
-
template<int tile_size = 2>
struct BagToFrames Public Types
-
using ApproxRecon = event_image_reconstruction_fibar::ApproxReconstructor<EventPacket, EventPacket::ConstSharedPtr, Image, Image::ConstSharedPtr, rclcpp::Time, tile_size>
Public Static Functions
-
static inline size_t processFreeRunning(double fps, rosbag2_cpp::Reader &reader, bool syncOnSensorTime, std::unordered_map<std::string, ApproxRecon> *recons)
-
static inline std::vector<std::pair<uint64_t, uint64_t>> readTimeStamps(const std::string &fn)
-
static inline size_t processOnTimeStamps(const std::string &tsFile, rosbag2_cpp::Reader &reader, bool syncOnSensorTime, std::unordered_map<std::string, ApproxRecon> *recons)
-
static inline void addFrameTime(std::unordered_map<std::string, ApproxRecon> *recons, const rclcpp::Time &t)
-
static inline void printPerformanceStatistics(const std::unordered_map<std::string, ApproxRecon> &recons)
-
static inline size_t processFrameBased(const std::vector<std::string> &ft, const std::unordered_map<std::string, std::string> &topicToType, rosbag2_cpp::Reader &reader, std::unordered_map<std::string, ApproxRecon> *recons, OutBagWriter *writer)
-
static inline std::unordered_map<std::string, std::string> getTopicMetaData(rosbag2_cpp::Reader &reader, const std::vector<std::string> &ft, std::vector<std::string> *uncomp, std::vector<std::string> *comp)
-
static inline size_t process_bag(const std::string &inBagName, const std::string &outBagName, const std::string &timeStampFile, const std::vector<std::string> &inTopics, const std::vector<std::string> &outTopics, const std::vector<std::string> &frameTopics, int cutoffPeriod, double fillRatio, bool hasSyncCable, double fps, bool writePNG, bool activePixels = false, const std::string &scaleFile = std::string())
-
using ApproxRecon = event_image_reconstruction_fibar::ApproxReconstructor<EventPacket, EventPacket::ConstSharedPtr, Image, Image::ConstSharedPtr, rclcpp::Time, tile_size>