#include <ros/publisher.h>#include <ros/subscriber.h>#include <ros/node_handle.h>#include <sensor_msgs/Image.h>#include <cv_bridge/cv_bridge.h>#include <opencv2/core/core.hpp>#include <opencv2/imgproc/imgproc.hpp>#include <opencv2/gpu/gpu.hpp>#include <fstream>#include <cstdlib>#include <ros/ros.h>#include <cv.h>#include <opencv2/highgui/highgui.hpp>#include <youbot_overhead_vision/markerCoords.h>#include <youbot_overhead_vision/CalibCameraImg.h>#include <youbot_overhead_vision/PositionFromCamera.h>#include "yaml-cpp/yaml.h"#include "calibTree.h"

Go to the source code of this file.
Classes | |
| class | imageCalibration |
| This class reads in raw images and publishes the location of the robot as well as a black and white occupancy. More... | |
| struct | imageCalibration::markerPoints |
Defines | |
| #define | BACK_EXTENDED 28 |
| #define | BOTH_CAMERAS 3 |
| #define | CALIB_ACCURACY 10 |
| #define | DIAG_MARKER_DIST 54 |
| #define | DST_BOUND_THRESH 50 |
| #define | ENCODING "rgb8" |
| #define | FLOOR 4 |
| #define | FRAME_ID "calibration" |
| #define | FRONT_EXTENDED 33 |
| #define | FRONT_MARKER_DIST 36 |
| #define | LEFT_EXTENDED 19 |
| #define | MARKER_ACCURACY 8 |
| #define | MARKER_CLUSTER_RADIUS 10 |
| #define | MAX_BOUND_LENGTH 120 |
| #define | MAX_BOUND_WIDTH 80 |
| #define | MIN_BOUND_LENGTH 77 |
| #define | MIN_BOUND_WIDTH 45 |
| #define | MIN_MARKER_PIXELS 6 |
| #define | NORTH_CAMERA 1 |
| #define | NOT_SET 5 |
| #define | OVERHEAD_NORTH "/logitech_9000_camera1/image_raw" |
| #define | OVERHEAD_SOUTH "/logitech_9000_camera2/image_raw" |
| #define | PI 3.14159 |
| #define | REAL_OVERLAP 62 |
| #define | RIGHT_EXTENDED 19 |
| #define | ROBOT_LEFT_BACK 2 |
| #define | ROBOT_LEFT_FRONT 0 |
| #define | ROBOT_RIGHT_BACK 3 |
| #define | ROBOT_RIGHT_FRONT 1 |
| #define | SIDE_MARKER_DIST 41 |
| #define | SIM_OVERLAP 30 |
| #define | SOUTH_CAMERA 2 |
| #define BACK_EXTENDED 28 |
Definition at line 60 of file image_calibration.h.
| #define BOTH_CAMERAS 3 |
Definition at line 79 of file image_calibration.h.
| #define CALIB_ACCURACY 10 |
Definition at line 31 of file image_calibration.h.
| #define DIAG_MARKER_DIST 54 |
Definition at line 66 of file image_calibration.h.
| #define DST_BOUND_THRESH 50 |
Definition at line 55 of file image_calibration.h.
| #define ENCODING "rgb8" |
Definition at line 29 of file image_calibration.h.
| #define FLOOR 4 |
Definition at line 43 of file image_calibration.h.
| #define FRAME_ID "calibration" |
Definition at line 30 of file image_calibration.h.
| #define FRONT_EXTENDED 33 |
Definition at line 58 of file image_calibration.h.
| #define FRONT_MARKER_DIST 36 |
Definition at line 65 of file image_calibration.h.
| #define LEFT_EXTENDED 19 |
Definition at line 61 of file image_calibration.h.
| #define MARKER_ACCURACY 8 |
Definition at line 67 of file image_calibration.h.
| #define MARKER_CLUSTER_RADIUS 10 |
Definition at line 48 of file image_calibration.h.
| #define MAX_BOUND_LENGTH 120 |
Definition at line 54 of file image_calibration.h.
| #define MAX_BOUND_WIDTH 80 |
Definition at line 53 of file image_calibration.h.
| #define MIN_BOUND_LENGTH 77 |
Definition at line 52 of file image_calibration.h.
| #define MIN_BOUND_WIDTH 45 |
Definition at line 51 of file image_calibration.h.
| #define MIN_MARKER_PIXELS 6 |
Definition at line 47 of file image_calibration.h.
| #define NORTH_CAMERA 1 |
Definition at line 77 of file image_calibration.h.
| #define NOT_SET 5 |
Definition at line 44 of file image_calibration.h.
| #define OVERHEAD_NORTH "/logitech_9000_camera1/image_raw" |
Definition at line 70 of file image_calibration.h.
| #define OVERHEAD_SOUTH "/logitech_9000_camera2/image_raw" |
Definition at line 71 of file image_calibration.h.
| #define PI 3.14159 |
Definition at line 81 of file image_calibration.h.
| #define REAL_OVERLAP 62 |
Definition at line 75 of file image_calibration.h.
| #define RIGHT_EXTENDED 19 |
Definition at line 59 of file image_calibration.h.
| #define ROBOT_LEFT_BACK 2 |
Definition at line 41 of file image_calibration.h.
| #define ROBOT_LEFT_FRONT 0 |
Definition at line 39 of file image_calibration.h.
| #define ROBOT_RIGHT_BACK 3 |
Definition at line 42 of file image_calibration.h.
| #define ROBOT_RIGHT_FRONT 1 |
Definition at line 40 of file image_calibration.h.
| #define SIDE_MARKER_DIST 41 |
Definition at line 64 of file image_calibration.h.
| #define SIM_OVERLAP 30 |
Definition at line 74 of file image_calibration.h.
| #define SOUTH_CAMERA 2 |
Definition at line 78 of file image_calibration.h.