standalone
main.cpp
Go to the documentation of this file.
1
// Copyright (c) 2020-2021 Pilz GmbH & Co. KG
2
//
3
// This program is free software: you can redistribute it and/or modify
4
// it under the terms of the GNU Lesser General Public License as published by
5
// the Free Software Foundation, either version 3 of the License, or
6
// (at your option) any later version.
7
//
8
// This program is distributed in the hope that it will be useful,
9
// but WITHOUT ANY WARRANTY; without even the implied warranty of
10
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11
// GNU Lesser General Public License for more details.
12
//
13
// You should have received a copy of the GNU Lesser General Public License
14
// along with this program. If not, see <https://www.gnu.org/licenses/>.
15
16
#include <chrono>
17
#include <string>
18
#include <thread>
19
20
#include <
psen_scan_v2_standalone/core.h
>
21
22
using namespace
psen_scan_v2_standalone
;
23
24
/*
25
* In this section we declare all necessary configuration parameters
26
*/
27
const
std::string
SCANNER_IP
{
"192.168.0.10"
};
28
// Start- and end-angle have been configured to be in the middle of the scan range.
29
const
util::TenthOfDegree
ANGLE_START
{
data_conversion_layer::degreeToTenthDegree
(137) };
30
const
util::TenthOfDegree
ANGLE_END
{
data_conversion_layer::degreeToTenthDegree
(138) };
31
32
/*
33
* This function is used as a callback every time a new laserscan is received. It is skipped for Scans that contain no
34
* measurement data. This can happen with smaller scan ranges.
35
*/
36
void
laserScanCallback
(
const
LaserScan
& scan)
37
{
38
// Other data fields are listed on
39
// https://docs.ros.org/en/melodic/api/psen_scan_v2/html/classpsen__scan__v2__standalone_1_1LaserScan.html
40
PSENSCAN_INFO_THROTTLE
(1
/* sec */
,
"laserScanCallback()"
,
"Ranges {}"
,
util::formatRange
(scan.
measurements
()));
41
}
42
43
int
main
(
int
argc,
char
** argv)
44
{
45
setLogLevel(CONSOLE_BRIDGE_LOG_INFO);
46
47
// Available configuration options are listed on
48
// http://docs.ros.org/en/melodic/api/psen_scan_v2/html/classpsen__scan__v2__standalone_1_1ScannerConfigurationBuilder.html
49
ScannerV2
scanner(
ScannerConfigurationBuilder
(
SCANNER_IP
).scanRange(
ScanRange
{
ANGLE_START
,
ANGLE_END
}),
50
laserScanCallback
);
51
52
scanner.
start
();
53
std::this_thread::sleep_for(std::chrono::seconds(10));
54
scanner.
stop
();
55
56
return
0;
57
}
laserScanCallback
void laserScanCallback(const LaserScan &scan)
Definition:
main.cpp:36
psen_scan_v2_standalone::ScannerV2::stop
std::future< void > stop() override
An exception is set in the returned future if the scanner stop was not successful.
Definition:
scanner_v2.cpp:90
main
int main(int argc, char **argv)
Definition:
main.cpp:43
ANGLE_START
const util::TenthOfDegree ANGLE_START
Definition:
main.cpp:29
psen_scan_v2_standalone::data_conversion_layer::degreeToTenthDegree
static int16_t degreeToTenthDegree(const double &angle_in_degree)
Definition:
angle_conversions.h:38
psen_scan_v2_standalone::ScannerV2
This is the implementation of the Scanner API defined by IScanner.
Definition:
scanner_v2.h:60
psen_scan_v2_standalone::util::formatRange
std::string formatRange(const T &range)
Definition:
format_range.h:38
PSENSCAN_INFO_THROTTLE
#define PSENSCAN_INFO_THROTTLE(period, name,...)
Definition:
logging.h:76
psen_scan_v2_standalone::ScannerV2::start
std::future< void > start() override
An exception is set in the returned future if the scanner start was not successful.
Definition:
scanner_v2.cpp:72
psen_scan_v2_standalone::ScannerConfigurationBuilder
Helper class to simplify/improve the construction of the psen_scan_v2_standalone::ScannerConfiguratio...
Definition:
scanner_config_builder.h:35
psen_scan_v2_standalone::LaserScan
This class represents a single laser scan in the <tf_prefix> target frame.
Definition:
laserscan.h:47
psen_scan_v2_standalone
Root namespace in which the software components to communicate with the scanner (firmware-version: 2)...
Definition:
udp_client.h:41
core.h
psen_scan_v2_standalone::LaserScan::measurements
const MeasurementData & measurements() const
Definition:
laserscan.cpp:141
psen_scan_v2_standalone::ScanRangeTemplated
Higher level data type storing the range in which the scanner takes measurements.
Definition:
scan_range.h:31
psen_scan_v2_standalone::util::TenthOfDegree
Helper class representing angles in tenth of degree.
Definition:
tenth_of_degree.h:34
SCANNER_IP
const std::string SCANNER_IP
Definition:
main.cpp:27
ANGLE_END
const util::TenthOfDegree ANGLE_END
Definition:
main.cpp:30
psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Jun 22 2024 02:46:11