forked from cyberbotics/webots
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathRangeFinder.cpp
More file actions
64 lines (51 loc) · 1.83 KB
/
RangeFinder.cpp
File metadata and controls
64 lines (51 loc) · 1.83 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
// Copyright 1996-2023 Cyberbotics Ltd.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// https://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#define WB_ALLOW_MIXING_C_AND_CPP_API
#include <webots/range_finder.h>
#include <webots/RangeFinder.hpp>
using namespace std;
using namespace webots;
void RangeFinder::enable(int sampling_period) {
wb_range_finder_enable(getTag(), sampling_period);
}
void RangeFinder::disable() {
wb_range_finder_disable(getTag());
}
int RangeFinder::getSamplingPeriod() const {
return wb_range_finder_get_sampling_period(getTag());
}
const float *RangeFinder::getRangeImage() const {
return wb_range_finder_get_range_image(getTag());
}
int RangeFinder::getWidth() const {
return wb_range_finder_get_width(getTag());
}
int RangeFinder::getHeight() const {
return wb_range_finder_get_height(getTag());
}
double RangeFinder::getFov() const {
return wb_range_finder_get_fov(getTag());
}
double RangeFinder::getMinRange() const {
return wb_range_finder_get_min_range(getTag());
}
double RangeFinder::getMaxRange() const {
return wb_range_finder_get_max_range(getTag());
}
int RangeFinder::saveImage(const string &filename, int quality) const {
return wb_range_finder_save_image(getTag(), filename.c_str(), quality);
}
float RangeFinder::rangeImageGetDepth(const float *image, int width, int x, int y) {
return wb_range_finder_image_get_depth(image, width, x, y);
}