src
camera.h
Go to the documentation of this file.
1
/****************************************************************************
2
*
3
* $Id: file.cpp 3496 2011-11-22 15:14:32Z fnovotny $
4
*
5
* This file is part of the ViSP software.
6
* Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7
*
8
* This software is free software; you can redistribute it and/or
9
* modify it under the terms of the GNU General Public License
10
* ("GPL") version 2 as published by the Free Software Foundation.
11
* See the file LICENSE.txt at the root directory of this source
12
* distribution for additional information about the GNU GPL.
13
*
14
* For using ViSP with software that can not be combined with the GNU
15
* GPL, please contact INRIA about acquiring a ViSP Professional
16
* Edition License.
17
*
18
* See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19
*
20
* This software was developed at:
21
* INRIA Rennes - Bretagne Atlantique
22
* Campus Universitaire de Beaulieu
23
* 35042 Rennes Cedex
24
* France
25
* http://www.irisa.fr/lagadic
26
*
27
* If you have questions regarding the use of this file, please contact
28
* INRIA at visp@inria.fr
29
*
30
* This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31
* WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32
*
33
* Contact visp@irisa.fr if any conditions of this licensing are
34
* not clear to you.
35
*
36
* Description:
37
*
38
*
39
* Authors:
40
* Filip Novotny
41
*
42
*
43
*****************************************************************************/
44
49
#include "
ros/ros.h
"
50
#include "sensor_msgs/Image.h"
51
#include "visp/vpVideoReader.h"
52
#include "sensor_msgs/SetCameraInfo.h"
53
#include <string>
54
55
#ifndef __visp_camera_calibration_CAMERA_H__
56
#define __visp_camera_calibration_CAMERA_H__
57
namespace
visp_camera_calibration
58
{
59
class
Camera
60
{
61
private
:
62
ros::NodeHandle
n_
;
63
ros::AsyncSpinner
spinner
;
64
ros::Publisher
raw_image_publisher_
;
65
ros::ServiceClient
calibrate_service_
;
66
67
ros::ServiceServer
set_camera_info_service_
;
68
69
unsigned
int
queue_size_
;
70
unsigned
int
nb_points_
;
71
72
vpVideoReader
reader_
;
73
vpImage<unsigned char>
img_
;
74
79
bool
setCameraInfoCallback
(sensor_msgs::SetCameraInfo::Request &req,
80
sensor_msgs::SetCameraInfo::Response &res);
81
83
typedef
boost::function<bool (sensor_msgs::SetCameraInfo::Request&,sensor_msgs::SetCameraInfo::Response& res)>
84
set_camera_info_service_callback_t
;
85
public
:
86
Camera
();
87
void
sendVideo
();
88
virtual
~Camera
();
89
};
90
}
91
#endif
/* CAMERA_H_ */
visp_camera_calibration::Camera::sendVideo
void sendVideo()
Definition:
camera.cpp:107
visp_camera_calibration::Camera::set_camera_info_service_
ros::ServiceServer set_camera_info_service_
Definition:
camera.h:67
visp_camera_calibration::Camera
Definition:
camera.h:59
ros::Publisher
ros.h
ros::AsyncSpinner
visp_camera_calibration::Camera::Camera
Camera()
Definition:
camera.cpp:70
visp_camera_calibration::Camera::set_camera_info_service_callback_t
boost::function< bool(sensor_msgs::SetCameraInfo::Request &, sensor_msgs::SetCameraInfo::Response &res)> set_camera_info_service_callback_t
service type declaration for calibrate service
Definition:
camera.h:84
visp_camera_calibration::Camera::queue_size_
unsigned int queue_size_
Definition:
camera.h:69
visp_camera_calibration::Camera::reader_
vpVideoReader reader_
Definition:
camera.h:72
ros::ServiceServer
visp_camera_calibration::Camera::nb_points_
unsigned int nb_points_
Definition:
camera.h:70
ros::ServiceClient
visp_camera_calibration::Camera::calibrate_service_
ros::ServiceClient calibrate_service_
Definition:
camera.h:65
visp_camera_calibration::Camera::n_
ros::NodeHandle n_
Definition:
camera.h:62
visp_camera_calibration::Camera::~Camera
virtual ~Camera()
Definition:
camera.cpp:168
visp_camera_calibration::Camera::img_
vpImage< unsigned char > img_
Definition:
camera.h:73
visp_camera_calibration::Camera::setCameraInfoCallback
bool setCameraInfoCallback(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
service setting camera parameters.
Definition:
camera.cpp:152
visp_camera_calibration
Definition:
calibrator.cpp:60
visp_camera_calibration::Camera::spinner
ros::AsyncSpinner spinner
Definition:
camera.h:63
ros::NodeHandle
visp_camera_calibration::Camera::raw_image_publisher_
ros::Publisher raw_image_publisher_
Definition:
camera.h:64
visp_camera_calibration
Author(s): Filip Novotny
autogenerated on Sat Aug 24 2024 02:54:52