sick_nav_scandata.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * sick_nav_scandata defines the data telegrams from NAV-350.
4  *
5  * Copyright (C) 2023, Ing.-Buero Dr. Michael Lehning, Hildesheim
6  * Copyright (C) 2023, SICK AG, Waldkirch
7  * All rights reserved.
8  *
9 * Licensed under the Apache License, Version 2.0 (the "License");
10 * you may not use this file except in compliance with the License.
11 * You may obtain a copy of the License at
12 *
13 * http://www.apache.org/licenses/LICENSE-2.0
14 *
15 * Unless required by applicable law or agreed to in writing, software
16 * distributed under the License is distributed on an "AS IS" BASIS,
17 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18 * See the License for the specific language governing permissions and
19 * limitations under the License.
20 *
21 *
22 * All rights reserved.
23 *
24 * Redistribution and use in source and binary forms, with or without
25 * modification, are permitted provided that the following conditions are met:
26 *
27 * * Redistributions of source code must retain the above copyright
28 * notice, this list of conditions and the following disclaimer.
29 * * Redistributions in binary form must reproduce the above copyright
30 * notice, this list of conditions and the following disclaimer in the
31 * documentation and/or other materials provided with the distribution.
32 * * Neither the name of Osnabrueck University nor the names of its
33 * contributors may be used to endorse or promote products derived from
34 * this software without specific prior written permission.
35 * * Neither the name of SICK AG nor the names of its
36 * contributors may be used to endorse or promote products derived from
37 * this software without specific prior written permission
38 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
39 * contributors may be used to endorse or promote products derived from
40 * this software without specific prior written permission
41 *
42 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
43 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
44 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
45 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
46 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
47 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
48 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
49 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
50 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
51 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
52 * POSSIBILITY OF SUCH DAMAGE.
53  *
54  * Authors:
55  * Michael Lehning <michael.lehning@lehning.de>
56  *
57  */
58 
59 #ifndef SICK_NAV_SCANDATA_H_
60 #define SICK_NAV_SCANDATA_H_
61 
62 #include <string>
63 #include <vector>
64 
66 
67 namespace sick_scan_xd
68 {
71  {
72  public:
73  uint8_t outputMode = 0;
74  uint32_t timestamp = 0;
75  int32_t meanDev = 0;
76  uint8_t navMode = 0;
77  uint32_t infoState = 0;
78  uint8_t quantUsedReflectors = 0;
79  };
80 
83  {
84  public:
85  int32_t x = 0; // x-position in mm
86  int32_t y = 0; // y-position in mm
87  uint32_t phi = 0; // orientation in 0 ... 360000 mdeg
88  uint16_t optPoseDataValid = 0;
90  };
91 
94  {
95  public:
96  int32_t x = 0;
97  int32_t y = 0;
98  };
99 
102  {
103  public:
104  uint32_t dist = 0;
105  uint32_t phi = 0;
106  };
107 
110  {
111  public:
112  uint16_t localID = 0;
113  uint16_t globalID = 0;
114  uint8_t type = 0;
115  uint16_t subType = 0;
116  uint16_t quality = 0;
117  uint32_t timestamp = 0;
118  uint16_t size = 0;
119  uint16_t hitCount = 0;
120  uint16_t meanEcho = 0;
121  uint16_t startIndex = 0;
122  uint16_t endIndex = 0;
123  };
124 
127  {
128  public:
129  uint16_t cartesianDataValid = 0;
131  uint16_t polarDataValid = 0;
133  uint16_t optReflectorDataValid = 0;
135  std::string print()
136  {
137  std::stringstream s;
138  s << "cartesianDataValid=" << (int)cartesianDataValid << ", cartesianData.x=" << cartesianData.x << ", cartesianData.y=" << cartesianData.y
139  << ", polarDataValid=" << (int)polarDataValid << ", polarData.dist=" << polarData.dist << ", polarData.phi=" << polarData.phi
140  << ", optReflectorDataValid=" << (int)optReflectorDataValid << ", localID=" << optReflectorData.localID << ", globalID=" << optReflectorData.globalID << ", type=" << (int)optReflectorData.type << ", subType=" << (int)optReflectorData.subType
141  << ", quality=" << optReflectorData.quality << ", timestamp=" << optReflectorData.timestamp << ", size=" << optReflectorData.size << ", hitCount=" << optReflectorData.hitCount << ", meanEcho=" << optReflectorData.meanEcho
142  << ", startIndex=" << optReflectorData.startIndex << ", endIndex=" << optReflectorData.endIndex;
143  return s.str();
144  }
145  };
146 
149  {
150  public:
151  uint8_t landmarkFilter = 0;
152  uint16_t numReflectors = 0;
153  std::vector<NAV350ReflectorData> reflectors;
154  };
155 
158  {
159  public:
160  uint8_t errorCode = 0;
161  uint16_t landmarkDataValid = 0;
163  void print()
164  {
165  ROS_INFO_STREAM("NAV350LandmarkDataDoMappingResponse: errorCode=" << (int)errorCode << ", landmarkDataValid=" << (int)landmarkDataValid << ", landmarkFilter=" << (int)landmarkData.landmarkFilter << ", numReflectors=" << (int)landmarkData.numReflectors);
166  for(int reflector_cnt = 0; reflector_cnt < landmarkData.reflectors.size(); reflector_cnt++)
167  ROS_INFO_STREAM("NAV350LandmarkDataDoMappingResponse: reflector[" << reflector_cnt << "]={" << landmarkData.reflectors[reflector_cnt].print() << "}");
168  }
169  };
170 
173  {
174  public:
175  std::string contentType = ""; // "DIST1" or "ANGL1"
176  float scaleFactor = 0; // multiplier, always 1 for NAV350
177  float scaleOffset = 0; // offset, always 0 for NAV350
178  int32_t startAngle = 0; // 0 ... +360000 mdeg
179  uint16_t angleRes = 0; // angular step, in 1/1000 deg, 250 mdeg (fix)
180  uint32_t timestampStart = 0; // timestamp of scan start in ms
181  uint16_t numData = 0; // number of scan data
182  std::vector<uint32_t> data; // DIST in mm or ANGL in 1/10000 degree
183  };
184 
187  {
188  public:
189  std::string contentType = ""; // "RSSI1"
190  float scaleFactor = 0; // multiplier, always 1 for NAV350
191  float scaleOffset = 0; // offset, always 0 for NAV350
192  int32_t startAngle = 0; // 0 ... +360000 mdeg
193  uint16_t angleRes = 0; // angular step, in 1/1000 deg, 250 mdeg (fix)
194  uint32_t timestampStart = 0; // timestamp of scan start in ms
195  uint16_t numData = 0; // number of scan data
196  std::vector<uint16_t> data; // remission data
197  };
198 
201  {
202  public:
203  uint16_t version = 0;
204  uint8_t errorCode = 0;
205  uint8_t wait = 0;
206  uint8_t mask = 0;
207  uint16_t poseDataValid = 0;
209  uint16_t landmarkDataValid = 0;
211  uint16_t scanDataValid = 0;
212  std::vector<NAV350ScanData> scanData; // no scan data (scanDataValid = 0) or DIST1 scan data (scanDataValid = 1) or DIST1 + ANGL1 scan data (scanDataValid = 2)
213  uint16_t remissionDataValid = 0;
215  float angleOffset = (float)(-M_PI);
216  };
217 
218 
221  {
222  public:
223  uint16_t globID = 0;
224  int32_t x_mm;
225  int32_t y_mm;
226  uint8_t type = 0;
227  uint16_t subType = 0;
228  uint16_t size_mm;
229  std::vector<uint16_t> layerID;
230  };
231 
232 } /* namespace sick_scan_xd */
233 #endif /* SICK_NAV_SCANDATA_H_ */
sick_scan_xd::NAV350PolarData
Definition: sick_nav_scandata.h:101
sick_scan_xd::NAV350RemissionData::scaleOffset
float scaleOffset
Definition: sick_nav_scandata.h:191
sick_scan_xd::NAV350OptReflectorData::subType
uint16_t subType
Definition: sick_nav_scandata.h:115
sick_scan_xd::NAV350ImkLandmark::x_mm
int32_t x_mm
Definition: sick_nav_scandata.h:224
sick_scan_xd::NAV350mNPOSData::landmarkData
NAV350LandmarkData landmarkData
Definition: sick_nav_scandata.h:210
sick_scan_xd::NAV350OptReflectorData
Definition: sick_nav_scandata.h:109
sick_scan_xd::NAV350ReflectorData::print
std::string print()
Definition: sick_nav_scandata.h:135
sick_scan_xd::NAV350ImkLandmark
Definition: sick_nav_scandata.h:220
sick_scan_xd::NAV350mNPOSData::angleOffset
float angleOffset
Definition: sick_nav_scandata.h:215
sick_scan_xd::NAV350ReflectorData
Definition: sick_nav_scandata.h:126
sick_scan_xd::NAV350mNPOSData::remissionDataValid
uint16_t remissionDataValid
Definition: sick_nav_scandata.h:213
s
XmlRpcServer s
sick_scan_xd::NAV350ScanData::scaleOffset
float scaleOffset
Definition: sick_nav_scandata.h:177
sick_scan_xd::NAV350OptReflectorData::hitCount
uint16_t hitCount
Definition: sick_nav_scandata.h:119
sick_scan_xd::NAV350ScanData::timestampStart
uint32_t timestampStart
Definition: sick_nav_scandata.h:180
sick_scan_xd::NAV350PolarData::dist
uint32_t dist
Definition: sick_nav_scandata.h:104
sick_scan_xd::NAV350LandmarkDataDoMappingResponse
Definition: sick_nav_scandata.h:157
sick_scan_xd::NAV350CartesianData
Definition: sick_nav_scandata.h:93
sick_scan_xd::NAV350ImkLandmark::y_mm
int32_t y_mm
Definition: sick_nav_scandata.h:225
sick_scan_xd::NAV350OptPoseData::navMode
uint8_t navMode
Definition: sick_nav_scandata.h:76
sick_scan_xd::NAV350LandmarkDataDoMappingResponse::print
void print()
Definition: sick_nav_scandata.h:163
sick_scan_xd::NAV350ReflectorData::polarData
NAV350PolarData polarData
Definition: sick_nav_scandata.h:132
sick_scan_xd::NAV350OptPoseData::infoState
uint32_t infoState
Definition: sick_nav_scandata.h:77
sick_scan_xd::NAV350RemissionData::data
std::vector< uint16_t > data
Definition: sick_nav_scandata.h:196
sick_scan_xd::NAV350mNPOSData::scanData
std::vector< NAV350ScanData > scanData
Definition: sick_nav_scandata.h:212
sick_scan_xd::NAV350RemissionData::startAngle
int32_t startAngle
Definition: sick_nav_scandata.h:192
sick_scan_xd::NAV350mNPOSData::scanDataValid
uint16_t scanDataValid
Definition: sick_nav_scandata.h:211
sick_scan_xd::NAV350ImkLandmark::globID
uint16_t globID
Definition: sick_nav_scandata.h:223
sick_scan_xd::NAV350OptReflectorData::size
uint16_t size
Definition: sick_nav_scandata.h:118
sick_scan_xd::NAV350LandmarkData::landmarkFilter
uint8_t landmarkFilter
Definition: sick_nav_scandata.h:151
sick_scan_xd::NAV350LandmarkDataDoMappingResponse::errorCode
uint8_t errorCode
Definition: sick_nav_scandata.h:160
sick_scan_xd::NAV350RemissionData::scaleFactor
float scaleFactor
Definition: sick_nav_scandata.h:190
sick_scan_xd::NAV350ImkLandmark::subType
uint16_t subType
Definition: sick_nav_scandata.h:227
sick_scan_xd::NAV350mNPOSData
Definition: sick_nav_scandata.h:200
sick_scan_xd::NAV350RemissionData::numData
uint16_t numData
Definition: sick_nav_scandata.h:195
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_xd::NAV350PoseData::optPoseDataValid
uint16_t optPoseDataValid
Definition: sick_nav_scandata.h:88
sick_ros_wrapper.h
sick_scan_xd::NAV350ReflectorData::polarDataValid
uint16_t polarDataValid
Definition: sick_nav_scandata.h:131
sick_scan_xd::NAV350ScanData
Definition: sick_nav_scandata.h:172
sick_scan_xd::NAV350RemissionData::angleRes
uint16_t angleRes
Definition: sick_nav_scandata.h:193
sick_scan_xd::NAV350LandmarkData
Definition: sick_nav_scandata.h:148
sick_scan_xd::NAV350ScanData::startAngle
int32_t startAngle
Definition: sick_nav_scandata.h:178
sick_scan_xd::NAV350ImkLandmark::layerID
std::vector< uint16_t > layerID
Definition: sick_nav_scandata.h:229
sick_scan_xd::NAV350mNPOSData::mask
uint8_t mask
Definition: sick_nav_scandata.h:206
sick_scan_xd::NAV350OptReflectorData::endIndex
uint16_t endIndex
Definition: sick_nav_scandata.h:122
sick_scan_xd::NAV350OptReflectorData::localID
uint16_t localID
Definition: sick_nav_scandata.h:112
ROS_INFO_STREAM
#define ROS_INFO_STREAM(...)
Definition: sick_scan_ros2_example.cpp:71
sick_scan_xd::NAV350OptReflectorData::startIndex
uint16_t startIndex
Definition: sick_nav_scandata.h:121
sick_scan_xd::NAV350OptPoseData::quantUsedReflectors
uint8_t quantUsedReflectors
Definition: sick_nav_scandata.h:78
sick_scan_xd::NAV350OptReflectorData::meanEcho
uint16_t meanEcho
Definition: sick_nav_scandata.h:120
sick_scan_xd::NAV350OptReflectorData::timestamp
uint32_t timestamp
Definition: sick_nav_scandata.h:117
sick_scan_xd::NAV350LandmarkData::numReflectors
uint16_t numReflectors
Definition: sick_nav_scandata.h:152
sick_scan_xd::NAV350RemissionData::contentType
std::string contentType
Definition: sick_nav_scandata.h:189
sick_scan_xd::NAV350OptPoseData::meanDev
int32_t meanDev
Definition: sick_nav_scandata.h:75
sick_scan_xd::NAV350mNPOSData::version
uint16_t version
Definition: sick_nav_scandata.h:203
sick_scan_xd::NAV350ScanData::scaleFactor
float scaleFactor
Definition: sick_nav_scandata.h:176
sick_scan_xd::NAV350ImkLandmark::size_mm
uint16_t size_mm
Definition: sick_nav_scandata.h:228
sick_scan_xd::NAV350LandmarkData::reflectors
std::vector< NAV350ReflectorData > reflectors
Definition: sick_nav_scandata.h:153
sick_scan_xd::NAV350CartesianData::y
int32_t y
Definition: sick_nav_scandata.h:97
sick_scan_xd::NAV350OptPoseData
Definition: sick_nav_scandata.h:70
sick_scan_xd::NAV350mNPOSData::remissionData
NAV350RemissionData remissionData
Definition: sick_nav_scandata.h:214
sick_scan_xd::NAV350OptReflectorData::globalID
uint16_t globalID
Definition: sick_nav_scandata.h:113
sick_scan_xd::NAV350ScanData::contentType
std::string contentType
Definition: sick_nav_scandata.h:175
sick_scan_xd::NAV350ReflectorData::cartesianDataValid
uint16_t cartesianDataValid
Definition: sick_nav_scandata.h:129
sick_scan_xd::NAV350ScanData::data
std::vector< uint32_t > data
Definition: sick_nav_scandata.h:182
sick_scan_xd::NAV350ReflectorData::optReflectorDataValid
uint16_t optReflectorDataValid
Definition: sick_nav_scandata.h:133
sick_scan_xd::NAV350CartesianData::x
int32_t x
Definition: sick_nav_scandata.h:96
sick_scan_xd::NAV350PolarData::phi
uint32_t phi
Definition: sick_nav_scandata.h:105
sick_scan_xd::NAV350ScanData::numData
uint16_t numData
Definition: sick_nav_scandata.h:181
sick_scan_xd::NAV350ImkLandmark::type
uint8_t type
Definition: sick_nav_scandata.h:226
sick_scan_xd::NAV350RemissionData
Definition: sick_nav_scandata.h:186
sick_scan_xd::NAV350LandmarkDataDoMappingResponse::landmarkData
NAV350LandmarkData landmarkData
Definition: sick_nav_scandata.h:162
sick_scan_xd::NAV350ReflectorData::optReflectorData
NAV350OptReflectorData optReflectorData
Definition: sick_nav_scandata.h:134
sick_scan_xd::NAV350RemissionData::timestampStart
uint32_t timestampStart
Definition: sick_nav_scandata.h:194
sick_scan_xd::NAV350PoseData::optPoseData
NAV350OptPoseData optPoseData
Definition: sick_nav_scandata.h:89
sick_scan_xd::NAV350OptPoseData::outputMode
uint8_t outputMode
Definition: sick_nav_scandata.h:73
sick_scan_base.h
sick_scan_xd::NAV350mNPOSData::errorCode
uint8_t errorCode
Definition: sick_nav_scandata.h:204
sick_scan_xd::NAV350mNPOSData::landmarkDataValid
uint16_t landmarkDataValid
Definition: sick_nav_scandata.h:209
sick_scan_xd::NAV350OptReflectorData::type
uint8_t type
Definition: sick_nav_scandata.h:114
sick_scan_xd::NAV350mNPOSData::wait
uint8_t wait
Definition: sick_nav_scandata.h:205
sick_scan_xd::NAV350mNPOSData::poseDataValid
uint16_t poseDataValid
Definition: sick_nav_scandata.h:207
sick_scan_xd::NAV350PoseData::phi
uint32_t phi
Definition: sick_nav_scandata.h:87
sick_scan_xd::NAV350PoseData::x
int32_t x
Definition: sick_nav_scandata.h:85
sick_scan_xd::NAV350OptPoseData::timestamp
uint32_t timestamp
Definition: sick_nav_scandata.h:74
sick_scan_xd::NAV350OptReflectorData::quality
uint16_t quality
Definition: sick_nav_scandata.h:116
sick_scan_xd::NAV350ReflectorData::cartesianData
NAV350CartesianData cartesianData
Definition: sick_nav_scandata.h:130
sick_scan_xd::NAV350ScanData::angleRes
uint16_t angleRes
Definition: sick_nav_scandata.h:179
sick_scan_xd::NAV350PoseData
Definition: sick_nav_scandata.h:82
sick_scan_xd::NAV350PoseData::y
int32_t y
Definition: sick_nav_scandata.h:86
sick_scan_xd::NAV350mNPOSData::poseData
NAV350PoseData poseData
Definition: sick_nav_scandata.h:208
sick_scan_xd::NAV350LandmarkDataDoMappingResponse::landmarkDataValid
uint16_t landmarkDataValid
Definition: sick_nav_scandata.h:161


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10