This class allows for easy calibration file generation. More...
#include <create_calibs.h>
Public Member Functions | |
void | applyCalib (cv::Mat *image_msg, int camera) |
string | convertInt (int number) |
createCalibs () | |
void | getCalibration (int calibType, int calibR, int calibB, int calibG) |
void | imageCallback1 (const sensor_msgs::ImageConstPtr &image_msg) |
void | imageCallback2 (const sensor_msgs::ImageConstPtr &image_msg) |
void | saveCalibsToFiles () |
void | showImage () |
~createCalibs () | |
Public Attributes | |
int | blurringFactor |
int | calibAccuracy |
int | calibratingColor |
int | calibToggled |
calibTree * | calTree |
int | cameraShown |
int | colors [5][3] |
bool | escPressed |
bool | image1LoadedFlag |
bool | image2LoadedFlag |
bool | imagePaused |
ros::Subscriber | imgSub1 |
ros::Subscriber | imgSub2 |
cv_bridge::CvImagePtr | output_Img1 |
cv_bridge::CvImagePtr | output_Img2 |
ros::Publisher | pubImgCal |
cv_bridge::CvImagePtr | raw_Img1 |
cv_bridge::CvImagePtr | raw_Img2 |
int | realCameraOverlap |
int | seq_num |
bool | updatedImageFlag |
bool | useSim |
Private Attributes | |
string | boundaryImgFilename |
string | filenames [5] |
This class allows for easy calibration file generation.
This class is used by launching the youbot_overhead_vision_create_calibs.launch launch file. It creates a window with a camera feed from one of the overhead cameras. When launched, a list of usable keyboard commands is printed to the terminal. Left mouse button clicks add the point at the position of that click to the list of calibration color values. Points can be removed as well, and the list can be saved to the appropriate calibration files with the 's' key.
Definition at line 51 of file create_calibs.h.
Constructor function for the createCalibs class. Initializes all the state variables, publishers, and subscribers used in the program, gets the ROS params from the launch files (whether the robot is simulated, and the calibration file locations), and gets the calibration points from the calibration files.
ros::spin()
Definition at line 11 of file create_calibs.cpp.
Destructor
Definition at line 85 of file create_calibs.cpp.
void createCalibs::applyCalib | ( | cv::Mat * | image_msg, |
int | camera | ||
) |
This function applies a calibration file to the image
image_msg: contains the image being calibrated. | |
camera, marks which camera is currently being looked at. |
Definition at line 471 of file create_calibs.cpp.
string createCalibs::convertInt | ( | int | number | ) |
Converts an int to a string with that integer in it
number,: | the integer being put in the string. |
Definition at line 587 of file create_calibs.cpp.
void createCalibs::getCalibration | ( | int | calibType, |
int | calibR, | ||
int | calibB, | ||
int | calibG | ||
) |
Function gets the calibration info, including the type of calibration that needs to be applied, and the colors that should be applied for each type.
calibType: The type of calibration file applied | |
cameraNum: the camera on which the calibration file should be applied | |
CalibR: Red value for the color to use for the calibration | |
CalibB: Blue value for the color to use for the calibration | |
CalibG: Green value for the color to use for the calibration |
Definition at line 374 of file create_calibs.cpp.
void createCalibs::imageCallback1 | ( | const sensor_msgs::ImageConstPtr & | image_msg | ) |
Callback function for Camera 1 is called when a message is read on the /logitech_9000_camera1/image_raw topic The image is stored in raw_Img1, and the image1LoadedFlag is set to true, stating that an image was red from the north overhead camera. showImage() does not start processing the image until both image loaded flags are true, stating that an image was read from both camera topics.
image_msg,a | message containing the image that was read from the overhead_north camera |
Definition at line 428 of file create_calibs.cpp.
void createCalibs::imageCallback2 | ( | const sensor_msgs::ImageConstPtr & | image_msg | ) |
Callback function for Camera 2 is called when a message is read on the /logitech_9000_camera2/image_raw topic The image is stored in raw_Img2, and the image2LoadedFlag is set to true, stating that an image was red from the south overhead camera. showImage() does not start processing the image until both image loaded flags are true, stating that an image was read from both camera topics.
image_msg,a | message containing the image that was read from the overhead_south camera |
Definition at line 449 of file create_calibs.cpp.
void createCalibs::saveCalibsToFiles | ( | ) |
This function saves the calibrations to files for future access
Definition at line 529 of file create_calibs.cpp.
void createCalibs::showImage | ( | ) |
This function is constantly called to display the image stream, allow for user imput from keyboard and mouse to add/delete calibration points, modify blur and accuracy parameters,zoom into the image, switch cameras, and save calibrations to file. This function also uses the applyCalib function to apply calibrations to the raw images stored into raw_Img1 and rawImg2 to created the calibrated images.
Definition at line 90 of file create_calibs.cpp.
Definition at line 104 of file create_calibs.h.
string createCalibs::boundaryImgFilename [private] |
Definition at line 174 of file create_calibs.h.
Definition at line 56 of file create_calibs.h.
Definition at line 69 of file create_calibs.h.
Definition at line 75 of file create_calibs.h.
Definition at line 89 of file create_calibs.h.
Definition at line 72 of file create_calibs.h.
int createCalibs::colors[5][3] |
Definition at line 91 of file create_calibs.h.
Definition at line 59 of file create_calibs.h.
string createCalibs::filenames[5] [private] |
Definition at line 172 of file create_calibs.h.
Definition at line 81 of file create_calibs.h.
Definition at line 82 of file create_calibs.h.
Definition at line 66 of file create_calibs.h.
Definition at line 84 of file create_calibs.h.
Definition at line 85 of file create_calibs.h.
Definition at line 94 of file create_calibs.h.
Definition at line 95 of file create_calibs.h.
Definition at line 86 of file create_calibs.h.
Definition at line 98 of file create_calibs.h.
Definition at line 99 of file create_calibs.h.
Definition at line 78 of file create_calibs.h.
Definition at line 105 of file create_calibs.h.
Definition at line 102 of file create_calibs.h.
bool createCalibs::useSim |
Definition at line 63 of file create_calibs.h.