24 #include <boost/regex.hpp> 26 #include <sensor_msgs/Image.h> 27 #include <HalconCpp.h> 28 #include <boost/filesystem.hpp> 29 #include <Eigen/Dense> 64 std::string
trim(std::string input);
75 wxBitmap*
createBitmap(
const sensor_msgs::Image::ConstPtr& msg,
int width,
int height);
86 wxBitmap*
createBitmap(HalconCpp::HImage image,
int width,
int height);
104 void get_all_files_with_ext(
const boost::filesystem::path& root,
const std::string& ext, std::vector<boost::filesystem::path>& ret);
114 HalconCpp::HImage
drawBoundingBox(HalconCpp::HImage image, std::vector<Eigen::Vector2i> corner_points);
wxString trimDoubleString(wxString input)
Formats the given string by removing fractional zeros at the end of it.
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.
std::string trim(std::string input)
Removes spaces from the beginning and end of the given string.
const std::string ROTATIONTYPE_CYLINDER
const std::string ROTATIONTYPE_SPHERE
const std::string ROTATIONTYPE_NO_ROTATION
bool check_string_redex(std::string to_check, boost::regex regex)
Checks a string with the given regex.
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.
wxBitmap * createBitmap(const sensor_msgs::Image::ConstPtr &msg, int width, int height)
Converts a ros-image-message to a bitmap-file used by wxwidgets.
const std::string INPUT_FOLDER
const std::string OUTPUT_FOLDER