laserscan_conversions.h
Go to the documentation of this file.
1 // Copyright (c) 2020-2022 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 #ifndef PSEN_SCAN_V2_STANDALONE_LASERSCAN_CONVERSIONS_H
17 #define PSEN_SCAN_V2_STANDALONE_LASERSCAN_CONVERSIONS_H
18 
24 
26 
27 #include <algorithm>
28 #include <numeric>
29 #include <vector>
30 
32 {
33 namespace data_conversion_layer
34 {
38 class ScannerProtocolViolationError : public std::runtime_error
39 {
40 public:
41  ScannerProtocolViolationError(const std::string& msg) : std::runtime_error(msg){};
42 };
43 
48 {
49 public:
62  static LaserScan
63  toLaserScan(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs);
64 
65 private:
66  static std::vector<int> getFilledFramesIndicesSortedByThetaAngle(
67  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs);
68  static util::TenthOfDegree
69  calculateMaxAngle(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
70  const util::TenthOfDegree& min_angle);
71  static int64_t
72  calculateTimestamp(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
73  const std::vector<int>& filled_stamped_msgs_indices);
75  static void
76  validateMonitoringFrames(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
77  const std::vector<int>& sorted_stamped_msgs_indices);
78  static bool
79  allResolutionsMatch(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs);
80  static bool
81  allScanCountersMatch(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs);
82  static bool
83  thetaAnglesFitTogether(const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
84  const std::vector<int>& sorted_stamped_msgs_indices);
85 };
86 
88  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
89 {
90  if (stamped_msgs.empty())
91  {
92  throw ScannerProtocolViolationError("At least one monitoring frame is necessary to create a LaserScan");
93  }
94 
95  std::vector<int> sorted_stamped_msgs_indices = getFilledFramesIndicesSortedByThetaAngle(stamped_msgs);
96  validateMonitoringFrames(stamped_msgs, sorted_stamped_msgs_indices);
97 
98  const auto min_angle = stamped_msgs[sorted_stamped_msgs_indices[0]].msg_.fromTheta();
99  const auto max_angle = calculateMaxAngle(stamped_msgs, min_angle);
100 
101  const auto timestamp = calculateTimestamp(stamped_msgs, sorted_stamped_msgs_indices);
102  configuration::ScannerId scanner_id = stamped_msgs[sorted_stamped_msgs_indices[0]].msg_.scannerId();
103 
104  std::vector<double> measurements;
105  std::vector<double> intensities;
106  std::vector<IOState> io_states;
107 
108  for (auto index : sorted_stamped_msgs_indices)
109  {
110  measurements.insert(measurements.end(),
111  stamped_msgs[index].msg_.measurements().begin(),
112  stamped_msgs[index].msg_.measurements().end());
113  if (stamped_msgs[index].msg_.hasIntensitiesField())
114  {
115  intensities.insert(intensities.end(),
116  stamped_msgs[index].msg_.intensities().begin(),
117  stamped_msgs[index].msg_.intensities().end());
118  }
119  }
120 
121  // Issue #320: Only for the io_states, we follow reception order instead Theta order.
122  // Other wise: index=0 who is the bigger Theta and correspond to the first io_state of the
123  // frame is placed at last item of vector io_states, and it provokes that io_states flicks.
124  for (const auto& single_msg : stamped_msgs)
125  {
126  if (single_msg.msg_.hasIOPinField())
127  {
128  PSENSCAN_DEBUG("io_states: ",
129  "stamp_: {} fromTheta: {} ioPinDate: {} ",
130  single_msg.stamp_,
131  std::to_string(single_msg.msg_.fromTheta().toRad()),
132  util::formatRange(single_msg.msg_.iOPinData().input_state));
133 
134  io_states.emplace_back(single_msg.msg_.iOPinData(), single_msg.stamp_);
135  }
136  }
137 
138  LaserScan scan(stamped_msgs[0].msg_.resolution(),
139  min_angle,
140  max_angle,
141  stamped_msgs[0].msg_.scanCounter(),
142  stamped_msgs[sorted_stamped_msgs_indices.back()].msg_.activeZoneset(),
143  timestamp,
144  scanner_id);
145 
146  scan.measurements(measurements);
147  scan.intensities(intensities);
148  scan.ioStates(io_states);
149 
150  return scan;
151 }
152 
154  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
155 {
156  std::vector<int> sorted_filled_stamped_msgs_indices(stamped_msgs.size());
157  std::iota(sorted_filled_stamped_msgs_indices.begin(), sorted_filled_stamped_msgs_indices.end(), 0);
158  std::sort(sorted_filled_stamped_msgs_indices.begin(),
159  sorted_filled_stamped_msgs_indices.end(),
160  [&stamped_msgs](int i1, int i2) {
161  return stamped_msgs[i1].msg_.fromTheta() < stamped_msgs[i2].msg_.fromTheta();
162  });
163 
164  // The following contains a missing line in the coverage report, which does not make sense.
165  // LCOV_EXCL_START
166  sorted_filled_stamped_msgs_indices.erase(
167  std::remove_if(sorted_filled_stamped_msgs_indices.begin(),
168  sorted_filled_stamped_msgs_indices.end(),
169  [&stamped_msgs](int i) { return stamped_msgs[i].msg_.measurements().empty(); }),
170  sorted_filled_stamped_msgs_indices.end());
171  // LCOV_EXCL_STOP
172 
173  return sorted_filled_stamped_msgs_indices;
174 }
175 
177  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
178  const util::TenthOfDegree& min_angle)
179 {
180  const auto resolution = stamped_msgs[0].msg_.resolution();
181  const uint16_t number_of_samples = std::accumulate(
182  stamped_msgs.begin(), stamped_msgs.end(), uint16_t{ 0 }, [](uint16_t total, const auto& stamped_msg) {
183  return total + stamped_msg.msg_.measurements().size();
184  });
185  return min_angle + resolution * static_cast<int>(number_of_samples - 1);
186 }
187 
189  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
190  const std::vector<int>& filled_stamped_msgs_indices)
191 {
192  const auto it = std::min_element(
193  filled_stamped_msgs_indices.begin(), filled_stamped_msgs_indices.end(), [&stamped_msgs](int i, int j) {
194  return stamped_msgs[i].stamp_ < stamped_msgs[j].stamp_;
195  }); // determines stamped_msg with smallest stamp
196  return calculateFirstRayTime(stamped_msgs[*it]);
197 }
198 
199 inline int64_t
201 {
202  const double time_per_scan_in_ns{ configuration::TIME_PER_SCAN_IN_S * 1000000000.0 };
203  const double scan_interval_in_degree{ stamped_msg.msg_.resolution().value() *
204  (stamped_msg.msg_.measurements().size() - 1) / 10.0 };
205  return stamped_msg.stamp_ - static_cast<int64_t>(std::round(scan_interval_in_degree * time_per_scan_in_ns / 360.0));
206 }
207 
209  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
210  const std::vector<int>& sorted_stamped_msgs_indices)
211 {
212  if (!allResolutionsMatch(stamped_msgs))
213  {
214  throw ScannerProtocolViolationError("The resolution of all monitoring frames has to be the same.");
215  }
216  else if (!allScanCountersMatch(stamped_msgs))
217  {
218  throw ScannerProtocolViolationError("The scan counters of all monitoring frames have to be the same.");
219  }
220  else if (!thetaAnglesFitTogether(stamped_msgs, sorted_stamped_msgs_indices))
221  {
222  throw ScannerProtocolViolationError("The monitoring frame ranges do not cover the whole scan range");
223  }
224 }
225 
227  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
228 {
229  const auto resolution = stamped_msgs[0].msg_.resolution();
230  return std::all_of(stamped_msgs.begin(), stamped_msgs.end(), [resolution](const auto& stamped_msg) {
231  return stamped_msg.msg_.resolution() == resolution;
232  });
233 }
234 
236  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
237 {
238  const auto scan_counter = stamped_msgs[0].msg_.scanCounter();
239  return std::all_of(stamped_msgs.begin(), stamped_msgs.end(), [scan_counter](const auto& stamped_msg) {
240  return stamped_msg.msg_.scanCounter() == scan_counter;
241  });
242 }
243 
245  const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs,
246  const std::vector<int>& sorted_filled_stamped_msgs_indices)
247 {
248  util::TenthOfDegree last_end = stamped_msgs[sorted_filled_stamped_msgs_indices[0]].msg_.fromTheta();
249  for (auto index : sorted_filled_stamped_msgs_indices)
250  {
251  const auto& stamped_msg = stamped_msgs[index];
252  if (last_end != stamped_msg.msg_.fromTheta())
253  {
254  return false;
255  }
256  last_end = stamped_msg.msg_.fromTheta() +
257  stamped_msg.msg_.resolution() * static_cast<int>(stamped_msg.msg_.measurements().size());
258  }
259  return true;
260 }
261 
262 } // namespace data_conversion_layer
263 } // namespace psen_scan_v2_standalone
264 
265 #endif // PSEN_SCAN_V2_STANDALONE_LASERSCAN_CONVERSIONS_H
psen_scan_v2_standalone::configuration::TIME_PER_SCAN_IN_S
static constexpr double TIME_PER_SCAN_IN_S
Definition: default_parameters.h:45
psen_scan_v2_standalone::configuration::ScannerId
ScannerId
Definition: scanner_ids.h:27
psen_scan_v2_standalone::data_conversion_layer::monitoring_frame::MessageStamped::msg_
Message msg_
Definition: monitoring_frame_msg.h:111
monitoring_frame_msg.h
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::allScanCountersMatch
static bool allScanCountersMatch(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs)
Definition: laserscan_conversions.h:235
psen_scan_v2_standalone::data_conversion_layer::ScannerProtocolViolationError::ScannerProtocolViolationError
ScannerProtocolViolationError(const std::string &msg)
Definition: laserscan_conversions.h:41
psen_scan_v2_standalone::LaserScan::ioStates
const IOData & ioStates() const
Definition: laserscan.cpp:198
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::thetaAnglesFitTogether
static bool thetaAnglesFitTogether(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs, const std::vector< int > &sorted_stamped_msgs_indices)
Definition: laserscan_conversions.h:244
PSENSCAN_DEBUG
#define PSENSCAN_DEBUG(name,...)
Definition: logging.h:63
psen_scan_v2_standalone::data_conversion_layer::ScannerProtocolViolationError
: Exception thrown if data received from the scanner hardware could not be processed according to pro...
Definition: laserscan_conversions.h:38
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::allResolutionsMatch
static bool allResolutionsMatch(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs)
Definition: laserscan_conversions.h:226
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::toLaserScan
static LaserScan toLaserScan(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs)
Converts monitoring_frames of a scan_round to the user friendly LaserScan type sent by the IScanner::...
Definition: laserscan_conversions.h:87
psen_scan_v2_standalone::util::TenthOfDegree::value
constexpr int16_t value() const
Definition: tenth_of_degree.h:49
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::calculateMaxAngle
static util::TenthOfDegree calculateMaxAngle(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs, const util::TenthOfDegree &min_angle)
Definition: laserscan_conversions.h:176
psen_scan_v2_standalone::data_conversion_layer::monitoring_frame::MessageStamped
Wrapping class for a Message and its corresponding timestamp.
Definition: monitoring_frame_msg.h:109
psen_scan_v2_standalone::util::formatRange
std::string formatRange(const T &range)
Definition: format_range.h:38
psen_scan_v2_standalone::LaserScan::intensities
const IntensityData & intensities() const
Definition: laserscan.cpp:171
psen_scan_v2_standalone::data_conversion_layer::monitoring_frame::Message::measurements
const std::vector< double > & measurements() const
Definition: monitoring_frame_msg.cpp:82
psen_scan_v2_standalone::data_conversion_layer::monitoring_frame::MessageStamped::stamp_
int64_t stamp_
Definition: monitoring_frame_msg.h:113
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::calculateFirstRayTime
static int64_t calculateFirstRayTime(const data_conversion_layer::monitoring_frame::MessageStamped &stamped_msg)
Definition: laserscan_conversions.h:200
scanner_ids.h
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter
: Responsible for converting Monitoring frames into LaserScan messages.
Definition: laserscan_conversions.h:47
default_parameters.h
std
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::calculateTimestamp
static int64_t calculateTimestamp(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs, const std::vector< int > &filled_stamped_msgs_indices)
Definition: laserscan_conversions.h:188
psen_scan_v2_standalone::LaserScan
This class represents a single laser scan in the <tf_prefix> target frame.
Definition: laserscan.h:47
logging.h
psen_scan_v2_standalone
Root namespace in which the software components to communicate with the scanner (firmware-version: 2)...
Definition: udp_client.h:41
psen_scan_v2_standalone::LaserScan::measurements
const MeasurementData & measurements() const
Definition: laserscan.cpp:141
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::validateMonitoringFrames
static void validateMonitoringFrames(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs, const std::vector< int > &sorted_stamped_msgs_indices)
Definition: laserscan_conversions.h:208
psen_scan_v2_standalone::data_conversion_layer::LaserScanConverter::getFilledFramesIndicesSortedByThetaAngle
static std::vector< int > getFilledFramesIndicesSortedByThetaAngle(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs)
Definition: laserscan_conversions.h:153
angle_conversions.h
laserscan.h
psen_scan_v2_standalone::data_conversion_layer::monitoring_frame::Message::resolution
util::TenthOfDegree resolution() const
Definition: monitoring_frame_msg.cpp:41
psen_scan_v2_standalone::util::TenthOfDegree
Helper class representing angles in tenth of degree.
Definition: tenth_of_degree.h:34


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Jun 22 2024 02:46:11