This class reads in raw images and publishes the location of the robot as well as a black and white occupancy. More...
#include <image_calibration.h>
Classes | |
struct | markerPoints |
Public Member Functions | |
void | addClusters (vector< int > *ImageXCoords, vector< int > *ImageYCoords) |
void | addMarkerPoint (int pointX, int pointY, int calibType) |
void | applyBoundingBox (cv::Mat *image, cv::RotatedRect rect) |
void | applyCalib () |
bool | applyCalibToPixel (int index, int calibType, cv_bridge::CvImagePtr image_msg, int camera) |
string | convertInt (int number) |
bool | extrapolateMarkers (vector< int > *ImageXCoords, vector< int > *ImageYCoords) |
vector< cv::RotatedRect > | findBoundingBox (cv::Mat image, int xpos, int ypos, int *minDstIndex) |
void | freerobotVector () |
void | getCalibration (int calibType, int calibR, int calibB, int calibG) |
imageCalibration () | |
void | imageCallback1 (const sensor_msgs::ImageConstPtr &image_msg) |
void | imageCallback2 (const sensor_msgs::ImageConstPtr &image_msg) |
void | processImage () |
void | removeRobot (vector< int > xCoords, vector< int > yCoords, int xpos, int ypos) |
void | resetForNextFrame () |
~imageCalibration () | |
Public Attributes | |
int | blurringFactor |
int | calibAccuracy |
calibTree * | calTree |
int | colors [6][3] |
int | count |
ros::Subscriber | imgSub1 |
ros::Subscriber | imgSub2 |
int | lastFrameMidpointX |
int | lastFrameMidpointY |
cv_bridge::CvImagePtr | output_Img1 |
cv_bridge::CvImagePtr | output_Img2 |
cv::Mat | pastObstImg |
ros::Publisher | pubImgCal |
ros::Publisher | pubRobotPosition |
cv_bridge::CvImagePtr | raw_Img1 |
cv_bridge::CvImagePtr | raw_Img2 |
vector< markerPoints > | robotMarkersVect |
cv::Mat | roomBoundary |
int | seq_num |
ros::ServiceServer | service |
bool | updatedImageFlag |
bool | useSim |
Private Attributes | |
string | filenames [5] |
This class reads in raw images and publishes the location of the robot as well as a black and white occupancy.
The imageCalibration class is used by launching the youbot_overhead_vision.launch file, or as part of the path_planning launch. It reads in raw images from two different overhead cameras topics (real or simulated in gazebo) and applies calibration files to these images to generate a single black and white image which can be used as an occupancy grid by the navigation stack. The robot heading and location are also found and published to a topic. The launch file contains parameters containing the location of the calibration files and the origin of the images (simulation or real cameras). There are 5 different types of calibrations. These are the floor, and four different robot markers (Left back, right back, left front, and right front). The files corresponding to these have points stored in them with rgb values. Calibration involves looking if each pixel in the images are close enough to any of the rgb values in these files, and changing the pixel to match the calibration color if they are. The floor file also contains the calibAccuracy variable, which determines how much is "close enough", and the blur variable, which determines what kind of blur to apply to the image before applying the calibration. The class uses the calibTree class to manage and parse calibration structures.
Definition at line 92 of file image_calibration.h.
Constructor initializes parameters, publishers, and subscribers. This function also uses these parameters to get the calibration points from the calibration files, and generates the tree stored in calTree of all the calib objects for easier calibration point parsing.
Definition at line 16 of file image_calibration.cpp.
Definition at line 79 of file image_calibration.cpp.
void imageCalibration::addClusters | ( | vector< int > * | ImageXCoords, |
vector< int > * | ImageYCoords | ||
) |
This function scans the robotMarkersVect vector and removes clusters that have less than MIN_MARKER_PIXELS pixels. Once thats done, the function determins which clusters are most likely the robot,and adds these to the structure holding the 4 marker positions.
Definition at line 399 of file image_calibration.cpp.
void imageCalibration::addMarkerPoint | ( | int | pointX, |
int | pointY, | ||
int | calibType | ||
) |
This function adds marker points to the markerPoints struct, determining the clusters A cluster is defined by a set of at least MIN_MARKER_PIXELS pixels less than MARKER_CLUSTER_RADIUS away from the center of the cluster.
pointX,: | The x position of the pixel in the image message |
pointY,: | The y position of the pixel in the image message |
calibType,: | The calibration type being applied to the pixel |
Definition at line 360 of file image_calibration.cpp.
void imageCalibration::applyBoundingBox | ( | cv::Mat * | image, |
cv::RotatedRect | rect | ||
) |
Given a bounding box, removes everything in an image within that box
image,: | the image to apply the bounding box to |
rect,: | the bounding box |
Definition at line 852 of file image_calibration.cpp.
void imageCalibration::applyCalib | ( | ) |
This function applies a calibration file to the image. The tree generated in getCalibration() is used to parse the calibration point values in a rapid manner.
Definition at line 294 of file image_calibration.cpp.
bool imageCalibration::applyCalibToPixel | ( | int | index, |
int | calibType, | ||
cv_bridge::CvImagePtr | image_msg, | ||
int | camera | ||
) |
Helper function to applyCalib. Applys a specific calibration to a specific pixel.
index,: | marks the position of the pixel in the image data structure. |
calibType,: | marks what type of calibration file is being applied to the pixel |
image_msg,: | Contains the image being modified |
camera,: | the camera whos image is currently being analyzed |
string imageCalibration::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 867 of file image_calibration.cpp.
bool imageCalibration::extrapolateMarkers | ( | vector< int > * | ImageXCoords, |
vector< int > * | ImageYCoords | ||
) |
This function fills in missing marker points depending on the points previously found on the robot. [1] = ROBOT_RIGHT_FRONT [2] = ROBOT_LEFT_BACK [3] = ROBOT_RIGHT_BACK NOT_SET (-1) means the marker values are empty Assumes only 2 points, but works for 3 points as well.
ImageXCoords,: | A vector containing x-coordinates of the marker centers. |
ImageYCoords,: | A vector containing y-coordinates of the marker centers. |
Definition at line 543 of file image_calibration.cpp.
vector< cv::RotatedRect > imageCalibration::findBoundingBox | ( | cv::Mat | image, |
int | xpos, | ||
int | ypos, | ||
int * | minDstIndex | ||
) |
Uses edge detection to determine a bounding box around the robot
image,: | the calibrated image from the overhead cameras |
xpos,: | the x coordinate of the robot center |
ypos,: | the y coordinate of the robot center |
Definition at line 785 of file image_calibration.cpp.
void imageCalibration::freerobotVector | ( | ) |
This function cleans the robotMarkersVect structure
Definition at line 884 of file image_calibration.cpp.
void imageCalibration::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 | |
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 84 of file image_calibration.cpp.
void imageCalibration::imageCallback1 | ( | const sensor_msgs::ImageConstPtr & | image_msg | ) |
Callback function for Camera 1 is called when a message is read on the /overhead_north/image_raw topic
image_msg,a | structure containing the image acquired from the /overhead_north/image_raw topic |
Definition at line 263 of file image_calibration.cpp.
void imageCalibration::imageCallback2 | ( | const sensor_msgs::ImageConstPtr & | image_msg | ) |
Callback function for Camera 2 is called when a message is read on the /overhead_south/image_raw topic
image_msg,a | structure containing the image acquired from the /overhead_south/image_raw topic |
Definition at line 278 of file image_calibration.cpp.
void imageCalibration::processImage | ( | ) |
Function processes overhead camera images. The two raw images (stored in raw_Img1 and raw_Img2) are combined into one image, eliminating the overlap between them. Then, the applyCalib() is used to apply the calibration points to the pixels in the image if applicable. Robot positions are printed to the /image_calibration/position_from_camera topic. Modified camera images are sent to the /image_calibration/image_cal topic.
Definition at line 136 of file image_calibration.cpp.
void imageCalibration::removeRobot | ( | vector< int > | xCoords, |
vector< int > | yCoords, | ||
int | xpos, | ||
int | ypos | ||
) |
Removes the robot from the image so that the resulting map can be used for path planning.
xCoords,: | the x coordinates of the robot marker points |
yCoords,: | the y coordinates of the robot marker points. |
xpos,: | the x coordinate of the robot center. |
ypos,: | the y coordinate of the robot center. |
Definition at line 663 of file image_calibration.cpp.
void imageCalibration::resetForNextFrame | ( | ) |
This function resets the structure containing the markers found in the last image in preparation for the next frame.
Definition at line 874 of file image_calibration.cpp.
Definition at line 145 of file image_calibration.h.
Definition at line 103 of file image_calibration.h.
Definition at line 129 of file image_calibration.h.
int imageCalibration::colors[6][3] |
Definition at line 116 of file image_calibration.h.
Definition at line 200 of file image_calibration.h.
string imageCalibration::filenames[5] [private] |
Definition at line 278 of file image_calibration.h.
Definition at line 106 of file image_calibration.h.
Definition at line 107 of file image_calibration.h.
Definition at line 99 of file image_calibration.h.
Definition at line 100 of file image_calibration.h.
Definition at line 135 of file image_calibration.h.
Definition at line 136 of file image_calibration.h.
cv::Mat imageCalibration::pastObstImg |
Definition at line 149 of file image_calibration.h.
Definition at line 109 of file image_calibration.h.
Definition at line 110 of file image_calibration.h.
Definition at line 139 of file image_calibration.h.
Definition at line 140 of file image_calibration.h.
Definition at line 132 of file image_calibration.h.
cv::Mat imageCalibration::roomBoundary |
Definition at line 113 of file image_calibration.h.
Definition at line 146 of file image_calibration.h.
Definition at line 108 of file image_calibration.h.
Definition at line 143 of file image_calibration.h.
Definition at line 97 of file image_calibration.h.