#include <image_processing.h>
|
void | init () |
|
void | rawImageCallback (const sensor_msgs::Image::ConstPtr &image) |
| callback corresponding to the raw_image topic. Computes a cMo from selected points on the image. Projects all points of the model to match the image of the grid. Add the obtained calibration object to an internal calibration list. More...
|
|
bool | setCameraInfoBisCallback (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res) |
| service displaying. More...
|
|
Definition at line 64 of file image_processing.h.
subscriber type declaration for raw_image topic subscriber
Definition at line 107 of file image_processing.h.
visp_camera_calibration::ImageProcessing::ImageProcessing |
( |
| ) |
|
visp_camera_calibration::ImageProcessing::~ImageProcessing |
( |
| ) |
|
|
virtual |
void visp_camera_calibration::ImageProcessing::init |
( |
| ) |
|
|
private |
void visp_camera_calibration::ImageProcessing::interface |
( |
| ) |
|
void visp_camera_calibration::ImageProcessing::rawImageCallback |
( |
const sensor_msgs::Image::ConstPtr & |
image | ) |
|
|
private |
callback corresponding to the raw_image topic. Computes a cMo from selected points on the image. Projects all points of the model to match the image of the grid. Add the obtained calibration object to an internal calibration list.
- Parameters
-
image_and_points | image of the grid and selected keypoints to compute on |
Definition at line 179 of file image_processing.cpp.
bool visp_camera_calibration::ImageProcessing::setCameraInfoBisCallback |
( |
sensor_msgs::SetCameraInfo::Request & |
req, |
|
|
sensor_msgs::SetCameraInfo::Response & |
res |
|
) |
| |
|
private |
vpCameraParameters visp_camera_calibration::ImageProcessing::cam_ |
|
private |
vpImage<unsigned char> visp_camera_calibration::ImageProcessing::img_ |
|
private |
bool visp_camera_calibration::ImageProcessing::is_initialized |
|
private |
std::vector<vpPoint> visp_camera_calibration::ImageProcessing::model_points_ |
|
private |
bool visp_camera_calibration::ImageProcessing::pause_image_ |
|
private |
ros::Publisher visp_camera_calibration::ImageProcessing::point_correspondence_publisher_ |
|
private |
unsigned long visp_camera_calibration::ImageProcessing::queue_size_ |
|
private |
ros::Subscriber visp_camera_calibration::ImageProcessing::raw_image_subscriber_ |
|
private |
std::vector<vpPoint> visp_camera_calibration::ImageProcessing::selected_points_ |
|
private |
The documentation for this class was generated from the following files: