#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.
◆ raw_image_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
Definition at line 107 of file image_processing.h.
◆ set_camera_info_bis_service_callback_t
◆ ImageProcessing()
visp_camera_calibration::ImageProcessing::ImageProcessing |
( |
| ) |
|
◆ ~ImageProcessing()
visp_camera_calibration::ImageProcessing::~ImageProcessing |
( |
| ) |
|
|
virtual |
◆ init()
void visp_camera_calibration::ImageProcessing::init |
( |
| ) |
|
|
private |
◆ interface()
void visp_camera_calibration::ImageProcessing::interface |
( |
| ) |
|
◆ rawImageCallback()
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.
◆ setCameraInfoBisCallback()
bool visp_camera_calibration::ImageProcessing::setCameraInfoBisCallback |
( |
sensor_msgs::SetCameraInfo::Request & |
req, |
|
|
sensor_msgs::SetCameraInfo::Response & |
res |
|
) |
| |
|
private |
◆ calibrate_service_
◆ cam_
vpCameraParameters visp_camera_calibration::ImageProcessing::cam_ |
|
private |
◆ img_
vpImage<unsigned char> visp_camera_calibration::ImageProcessing::img_ |
|
private |
◆ is_initialized
bool visp_camera_calibration::ImageProcessing::is_initialized |
|
private |
◆ model_points_
std::vector<vpPoint> visp_camera_calibration::ImageProcessing::model_points_ |
|
private |
◆ n_
◆ pause_image_
bool visp_camera_calibration::ImageProcessing::pause_image_ |
|
private |
◆ point_correspondence_publisher_
ros::Publisher visp_camera_calibration::ImageProcessing::point_correspondence_publisher_ |
|
private |
◆ queue_size_
unsigned long visp_camera_calibration::ImageProcessing::queue_size_ |
|
private |
◆ raw_image_subscriber_
ros::Subscriber visp_camera_calibration::ImageProcessing::raw_image_subscriber_ |
|
private |
◆ selected_points_
std::vector<vpPoint> visp_camera_calibration::ImageProcessing::selected_points_ |
|
private |
◆ set_camera_info_bis_service_
◆ spinner_
The documentation for this class was generated from the following files: