Public Types | Public Member Functions | Private Member Functions | Private Attributes
visp_camera_calibration::ImageProcessing Class Reference

#include <image_processing.h>

List of all members.

Public Types

typedef boost::function< void(const
sensor_msgs::Image::ConstPtr &)> 
raw_image_subscriber_callback_t
 subscriber type declaration for raw_image topic subscriber
typedef boost::function< bool(sensor_msgs::SetCameraInfo::Request
&, sensor_msgs::SetCameraInfo::Response
&res)> 
set_camera_info_bis_service_callback_t
 service type declaration for calibrate service

Public Member Functions

 ImageProcessing ()
void interface ()
virtual ~ImageProcessing ()

Private Member Functions

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.
bool setCameraInfoBisCallback (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
 service displaying.

Private Attributes

ros::ServiceClient calibrate_service_
vpCameraParameters cam_
vpImage< unsigned char > img_
std::vector< vpPoint > model_points_
ros::NodeHandle n_
bool pause_image_
ros::Publisher point_correspondence_publisher_
unsigned long queue_size_
ros::Subscriber raw_image_subscriber_
std::vector< vpPoint > selected_points_
ros::ServiceServer set_camera_info_bis_service_
ros::AsyncSpinner spinner_

Detailed Description

Definition at line 64 of file image_processing.h.


Member Typedef Documentation

typedef boost::function<void (const sensor_msgs::Image::ConstPtr& )> visp_camera_calibration::ImageProcessing::raw_image_subscriber_callback_t

subscriber type declaration for raw_image topic subscriber

Definition at line 103 of file image_processing.h.

typedef boost::function<bool (sensor_msgs::SetCameraInfo::Request&,sensor_msgs::SetCameraInfo::Response& res)> visp_camera_calibration::ImageProcessing::set_camera_info_bis_service_callback_t

service type declaration for calibrate service

Definition at line 107 of file image_processing.h.


Constructor & Destructor Documentation

Definition at line 76 of file image_processing.cpp.

Definition at line 338 of file image_processing.cpp.


Member Function Documentation

Definition at line 327 of file image_processing.cpp.

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 170 of file image_processing.cpp.

bool visp_camera_calibration::ImageProcessing::setCameraInfoBisCallback ( sensor_msgs::SetCameraInfo::Request &  req,
sensor_msgs::SetCameraInfo::Response &  res 
) [private]

service displaying.

Definition at line 162 of file image_processing.cpp.


Member Data Documentation

Definition at line 76 of file image_processing.h.

vpCameraParameters visp_camera_calibration::ImageProcessing::cam_ [private]

Definition at line 83 of file image_processing.h.

vpImage<unsigned char> visp_camera_calibration::ImageProcessing::img_ [private]

Definition at line 78 of file image_processing.h.

Definition at line 81 of file image_processing.h.

Definition at line 66 of file image_processing.h.

Definition at line 70 of file image_processing.h.

Definition at line 73 of file image_processing.h.

Definition at line 69 of file image_processing.h.

Definition at line 72 of file image_processing.h.

Definition at line 80 of file image_processing.h.

Definition at line 75 of file image_processing.h.

Definition at line 67 of file image_processing.h.


The documentation for this class was generated from the following files:


visp_camera_calibration
Author(s): Filip Novotny
autogenerated on Sat Dec 28 2013 17:45:42