Functions | Variables
Utils.h File Reference
#include <boost/regex.hpp>
#include <wx/wx.h>
#include <sensor_msgs/Image.h>
#include <HalconCpp.h>
#include <boost/filesystem.hpp>
#include <Eigen/Dense>
Include dependency graph for Utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

bool check_string_redex (std::string to_check, boost::regex regex)
 Checks a string with the given regex.
wxBitmap * createBitmap (const sensor_msgs::Image::ConstPtr &msg, int width, int height)
 Converts a ros-image-message to a bitmap-file used by wxwidgets.
wxBitmap * createBitmap (HalconCpp::HImage image, int width, int height)
 Converts a halcon-image to a bitmap-file used by wxwidgets.
HalconCpp::HImage drawBoundingBox (HalconCpp::HImage image, std::vector< Eigen::Vector2i > corner_points)
 Draws a bounding box on the given image with the also given corner-points.
void get_all_files_with_ext (const boost::filesystem::path &root, const std::string &ext, std::vector< boost::filesystem::path > &ret)
 Gets all files in a directory with a specific extension.
std::string trim (std::string input)
 Removes spaces from the beginning and end of the given string.
wxString trimDoubleString (wxString input)
 Formats the given string by removing fractional zeros at the end of it.

Variables

const std::string INPUT_FOLDER = "/trainer_data/input"
const std::string OUTPUT_FOLDER = "/trainer_data/output"
const std::string ROTATIONTYPE_CYLINDER = "Cylinder"
const std::string ROTATIONTYPE_NO_ROTATION = "No Rotation"
const std::string ROTATIONTYPE_SPHERE = "Sphere"

Function Documentation

bool check_string_redex ( std::string  to_check,
boost::regex  regex 
)

Checks a string with the given regex.

Returns:
true if the string matches the given regex, false otherwise

Copyright (C) 2016, Allgeyer Tobias, Hutmacher Robin, Meißner Pascal

This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>.

Definition at line 27 of file Utils.cpp.

wxBitmap* createBitmap ( const sensor_msgs::Image::ConstPtr &  msg,
int  width,
int  height 
)

Converts a ros-image-message to a bitmap-file used by wxwidgets.

Parameters:
msgThe given ros-image-message
widthThe width of the converted image
heightThe height of the converted image
Returns:
The converted bitmap

Definition at line 40 of file Utils.cpp.

wxBitmap* createBitmap ( HalconCpp::HImage  image,
int  width,
int  height 
)

Converts a halcon-image to a bitmap-file used by wxwidgets.

Parameters:
imageThe given halcon-image
widthThe width of the converted image
heightThe height of the converted image
Returns:
The converted bitmap

Definition at line 71 of file Utils.cpp.

HalconCpp::HImage drawBoundingBox ( HalconCpp::HImage  image,
std::vector< Eigen::Vector2i >  corner_points 
)

Draws a bounding box on the given image with the also given corner-points.

Parameters:
imageThe image the bounding box is drawn on
corner_pointsThe points describing the corner points of the bounding box in the image
Returns:
The image with the bounding box

Definition at line 118 of file Utils.cpp.

void get_all_files_with_ext ( const boost::filesystem::path &  root,
const std::string &  ext,
std::vector< boost::filesystem::path > &  ret 
)

Gets all files in a directory with a specific extension.

Parameters:
rootThe given directory
extThe extension the files are chosen by
retThe list the found files are added to

Definition at line 103 of file Utils.cpp.

std::string trim ( std::string  input)

Removes spaces from the beginning and end of the given string.

Returns:
The trimmed string

Definition at line 34 of file Utils.cpp.

wxString trimDoubleString ( wxString  input)

Formats the given string by removing fractional zeros at the end of it.

Parameters:
inputThe given string
Returns:
The formatted string

Definition at line 86 of file Utils.cpp.


Variable Documentation

const std::string INPUT_FOLDER = "/trainer_data/input"

The input folder containing the data used for training (relative to package)

Definition at line 46 of file Utils.h.

const std::string OUTPUT_FOLDER = "/trainer_data/output"

The output folder the created trained object is written to (relative to package)

Definition at line 49 of file Utils.h.

const std::string ROTATIONTYPE_CYLINDER = "Cylinder"

Rotation type describing an object cylindrical symmetry

Definition at line 40 of file Utils.h.

const std::string ROTATIONTYPE_NO_ROTATION = "No Rotation"

Copyright (C) 2016, Allgeyer Tobias, Hutmacher Robin, Meißner Pascal

This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>. Global utility functions Rotation type describing an object without axial symmetry

Definition at line 37 of file Utils.h.

const std::string ROTATIONTYPE_SPHERE = "Sphere"

Rotation type describing an object with spherical symmetry

Definition at line 43 of file Utils.h.



asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Thu Jun 6 2019 17:57:29