50 #include "sensor_msgs/Image.h" 51 #include "sensor_msgs/SetCameraInfo.h" 52 #include "visp/vpImage.h" 53 #include "visp/vpPoint.h" 54 #include "visp/vpCameraParameters.h" 57 #include <boost/thread/thread.hpp> 60 #ifndef __visp_camera_calibration_IMAGE_PROCESSING_H__ 61 #define __visp_camera_calibration_IMAGE_PROCESSING_H__ 78 vpImage<unsigned char>
img_;
103 sensor_msgs::SetCameraInfo::Response &res);
106 typedef boost::function<void (const sensor_msgs::Image::ConstPtr& )>
110 typedef boost::function<bool (sensor_msgs::SetCameraInfo::Request&,sensor_msgs::SetCameraInfo::Response& res)>
std::vector< vpPoint > selected_points_
ros::Subscriber raw_image_subscriber_
unsigned long queue_size_
vpImage< unsigned char > img_
virtual ~ImageProcessing()
boost::function< void(const sensor_msgs::Image::ConstPtr &)> raw_image_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
void rawImageCallback(const sensor_msgs::Image::ConstPtr &image)
callback corresponding to the raw_image topic. Computes a cMo from selected points on the image...
bool setCameraInfoBisCallback(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
service displaying.
ros::Publisher point_correspondence_publisher_
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
std::vector< vpPoint > model_points_
ros::ServiceServer set_camera_info_bis_service_
ros::ServiceClient calibrate_service_
ros::AsyncSpinner spinner_