Main Page
Namespaces
Namespace List
Namespace Members
All
a
b
c
d
e
f
g
h
l
m
p
r
s
u
x
y
z
Functions
Variables
Typedefs
Enumerator
Classes
Class List
Class Hierarchy
Class Members
All
a
b
c
d
e
f
g
h
i
j
l
m
n
o
p
r
s
t
u
v
w
x
y
z
~
Functions
a
b
c
d
e
f
g
h
i
l
m
o
p
r
s
u
w
~
Variables
a
b
c
d
e
f
h
i
j
l
m
n
o
p
r
s
t
u
v
w
x
y
z
Typedefs
Files
File List
File Members
All
Functions
Variables
Macros
include
robot_calibration
capture
depth_camera.h
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2015-2016 Fetch Robotics Inc.
3
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
4
*
5
* Licensed under the Apache License, Version 2.0 (the "License");
6
* you may not use this file except in compliance with the License.
7
* You may obtain a copy of the License at
8
*
9
* http://www.apache.org/licenses/LICENSE-2.0
10
*
11
* Unless required by applicable law or agreed to in writing, software
12
* distributed under the License is distributed on an "AS IS" BASIS,
13
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14
* See the License for the specific language governing permissions and
15
* limitations under the License.
16
*/
17
18
// Author: Michael Ferguson
19
20
#ifndef ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
21
#define ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
22
23
#include <
ros/ros.h
>
24
#include <sensor_msgs/CameraInfo.h>
25
#include <robot_calibration_msgs/CalibrationData.h>
26
#include <robot_calibration_msgs/ExtendedCameraInfo.h>
27
28
namespace
robot_calibration
29
{
30
32
class
DepthCameraInfoManager
33
{
34
public
:
35
DepthCameraInfoManager
() :
camera_info_valid_
(false) {}
36
virtual
~DepthCameraInfoManager
() {}
37
38
bool
init
(
ros::NodeHandle
& n)
39
{
40
std::string topic_name;
41
n.
param
<std::string>(
"camera_info_topic"
, topic_name,
"/head_camera/depth/camera_info"
);
42
43
camera_info_subscriber_
= n.
subscribe
(topic_name,
44
1,
45
&
DepthCameraInfoManager::cameraInfoCallback
,
46
this
);
47
48
// Get parameters of drivers
49
std::string driver_name;
50
n.
param
<std::string>(
"camera_driver"
, driver_name,
"/head_camera/driver"
);
51
if
(!n.
getParam
(driver_name+
"/z_offset_mm"
,
z_offset_mm_
) ||
52
!n.
getParam
(driver_name+
"/z_scaling"
,
z_scaling_
))
53
{
54
ROS_ERROR
(
"%s is not set, are drivers running?"
,driver_name.c_str());
55
z_offset_mm_
= 0;
56
z_scaling_
= 1;
57
}
58
59
// Wait for camera_info
60
int
count = 25;
61
while
(--count)
62
{
63
if
(
camera_info_valid_
)
64
{
65
return
true
;
66
}
67
ros::Duration
(0.1).
sleep
();
68
ros::spinOnce
();
69
}
70
71
ROS_WARN
(
"CameraInfo receive timed out."
);
72
return
false
;
73
}
74
75
robot_calibration_msgs::ExtendedCameraInfo
getDepthCameraInfo
()
76
{
77
robot_calibration_msgs::ExtendedCameraInfo info;
78
info.camera_info = *
camera_info_ptr_
;
79
info.parameters.resize(2);
80
info.parameters[0].name =
"z_offset_mm"
;
81
info.parameters[0].value =
z_offset_mm_
;
82
info.parameters[1].name =
"z_scaling"
;
83
info.parameters[1].value =
z_scaling_
;
84
return
info;
85
}
86
87
private
:
88
void
cameraInfoCallback
(
const
sensor_msgs::CameraInfo::Ptr camera_info)
89
{
90
camera_info_ptr_
= camera_info;
91
camera_info_valid_
=
true
;
92
}
93
94
ros::Subscriber
camera_info_subscriber_
;
95
bool
camera_info_valid_
;
96
97
sensor_msgs::CameraInfo::Ptr
camera_info_ptr_
;
98
99
double
z_offset_mm_
;
100
double
z_scaling_
;
101
};
102
103
}
// namespace robot_calibration
104
105
#endif // ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
robot_calibration::DepthCameraInfoManager::cameraInfoCallback
void cameraInfoCallback(const sensor_msgs::CameraInfo::Ptr camera_info)
Definition:
depth_camera.h:88
robot_calibration::DepthCameraInfoManager::init
bool init(ros::NodeHandle &n)
Definition:
depth_camera.h:38
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
robot_calibration::DepthCameraInfoManager
Base class for a feature finder.
Definition:
depth_camera.h:32
ros::spinOnce
ROSCPP_DECL void spinOnce()
robot_calibration::DepthCameraInfoManager::camera_info_valid_
bool camera_info_valid_
Definition:
depth_camera.h:95
robot_calibration::DepthCameraInfoManager::~DepthCameraInfoManager
virtual ~DepthCameraInfoManager()
Definition:
depth_camera.h:36
robot_calibration::DepthCameraInfoManager::camera_info_subscriber_
ros::Subscriber camera_info_subscriber_
Definition:
depth_camera.h:94
ROS_ERROR
#define ROS_ERROR(...)
robot_calibration::DepthCameraInfoManager::z_scaling_
double z_scaling_
Definition:
depth_camera.h:100
ROS_WARN
#define ROS_WARN(...)
robot_calibration::DepthCameraInfoManager::z_offset_mm_
double z_offset_mm_
Definition:
depth_camera.h:99
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
robot_calibration
Calibration code lives under this namespace.
Definition:
base_calibration.h:28
ros::NodeHandle::param
T param(const std::string ¶m_name, const T &default_val) const
robot_calibration::DepthCameraInfoManager::DepthCameraInfoManager
DepthCameraInfoManager()
Definition:
depth_camera.h:35
ros::Duration::sleep
bool sleep() const
robot_calibration::DepthCameraInfoManager::camera_info_ptr_
sensor_msgs::CameraInfo::Ptr camera_info_ptr_
Definition:
depth_camera.h:97
robot_calibration::DepthCameraInfoManager::getDepthCameraInfo
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
Definition:
depth_camera.h:75
ros::Duration
ros::NodeHandle
ros::Subscriber
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01