sick_generic_radar.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  * Copyright (C) 2018, Ing.-Buero Dr. Michael Lehning, Hildesheim
4  * Copyright (C) 2018, SICK AG, Waldkirch
5  * All rights reserved.
6  *
7 * Licensed under the Apache License, Version 2.0 (the "License");
8 * you may not use this file except in compliance with the License.
9 * You may obtain a copy of the License at
10 *
11 * http://www.apache.org/licenses/LICENSE-2.0
12 *
13 * Unless required by applicable law or agreed to in writing, software
14 * distributed under the License is distributed on an "AS IS" BASIS,
15 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 * See the License for the specific language governing permissions and
17 * limitations under the License.
18 *
19 *
20 * All rights reserved.
21 *
22 * Redistribution and use in source and binary forms, with or without
23 * modification, are permitted provided that the following conditions are met:
24 *
25 * * Redistributions of source code must retain the above copyright
26 * notice, this list of conditions and the following disclaimer.
27 * * Redistributions in binary form must reproduce the above copyright
28 * notice, this list of conditions and the following disclaimer in the
29 * documentation and/or other materials provided with the distribution.
30 * * Neither the name of Osnabrueck University nor the names of its
31 * contributors may be used to endorse or promote products derived from
32 * this software without specific prior written permission.
33 * * Neither the name of SICK AG nor the names of its
34 * contributors may be used to endorse or promote products derived from
35 * this software without specific prior written permission
36 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
37 * contributors may be used to endorse or promote products derived from
38 * this software without specific prior written permission
39 *
40 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
41 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
42 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
43 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
44 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
45 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
46 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
47 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
48 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
49 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
50 * POSSIBILITY OF SUCH DAMAGE.
51  *
52  * Created on: 28th May 2018
53  *
54  * Authors:
55  * Michael Lehning <michael.lehning@lehning.de>
56  *
57  */
58 
59 #ifndef SICK_GENERIC_RADAR_H_
60 #define SICK_GENERIC_RADAR_H_
61 
62 #include <stdio.h>
63 #include <stdlib.h>
64 #include <string>
65 #include <string.h>
66 #include <vector>
67 
72 //#include <sick_scan/RadarScan.h> // generated by msg-generator
73 
76 
77 namespace sick_scan_xd
78 {
79 
81  {
82  public:
83  float Dist() const
84  { return dist; }
85 
86  void Dist(float val)
87  { dist = val; }
88 
89  float Azimuth() const
90  { return azimuth; }
91 
92  void Azimuth(float val)
93  { azimuth = val; }
94 
95  float Vrad() const
96  { return vrad; }
97 
98  void Vrad(float val)
99  { vrad = val; }
100 
101  float Ampl() const
102  { return ampl; }
103 
104  void Ampl(float val)
105  { ampl = val; }
106 
107  int Mode() const
108  { return mode; }
109 
110  void Mode(int val)
111  { mode = val; }
112 
113  private:
114  float dist;
115  float azimuth;
116  float vrad;
117  float ampl;
118  int mode;
119  };
120 
122  {
123  public:
124  float P3Dx() const
125  { return p3Dx; }
126 
127  void P3Dx(float val)
128  { p3Dx = val; }
129 
130  float P3Dy() const
131  { return p3Dy; }
132 
133  void P3Dy(float val)
134  { p3Dy = val; }
135 
136  float V3Dx() const
137  { return v3Dx; }
138 
139  void V3Dx(float val)
140  { v3Dx = val; }
141 
142  float V3Dy() const
143  { return v3Dy; }
144 
145  void V3Dy(float val)
146  { v3Dy = val; }
147 
148  float ObjLength() const
149  { return objLength; }
150 
151  void ObjLength(float val)
152  { objLength = val; }
153 
154  int ObjId() const
155  { return objId; }
156 
157  void ObjId(int val)
158  { objId = val; }
159 
160  private:
161  float p3Dx;
162  float p3Dy;
163  float v3Dx;
164  float v3Dy;
165  float objLength;
166  int objId;
167  };
168 
169 
171  {
172  private:
173  /* Here will be the instance stored. */
175 
176  /* Private constructor to prevent instancing. */
178 
179  void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern);
180 
181  bool emul = false;
182 
183  std::string radarName = "???"; // radar device type
186 
190 
191  sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy; // Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform)
193 
194  public:
195  /* Static access method. */
197 
198  void setEmulation(bool _emul);
199 
200  bool getEmulation(void);
201 
202  int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
203 
204  int parseRadarDatagram(char* datagram, size_t datagram_length, bool useBinaryProtocol,
205  sick_scan_msg::RadarScan* msgPtr,
206  std::vector<SickScanRadarObject>& objectList,
207  std::vector<SickScanRadarRawTarget>& rawTargetList, /* , SickScanConfig &config, */ // sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask);
208  int verboseLevel = 0);
209 
210  void simulateAsciiDatagram(unsigned char *receiveBuffer, int *actual_length);
211  void setNameOfRadar(const std::string& _radarName, RADAR_TYPE_ENUM _radarType)
212  {
213  radarName = _radarName;
214  radarType = _radarType;
215  }
216  std::string getNameOfRadar()
217  {
218  return(radarName);
219  }
220  };
221 
222 
223 #if 0
224  class SickScanRadar
225  {
226  public:
227  SickScanRadar(SickScanCommon *commonPtr_)
228  {
229  commonPtr = commonPtr_;
230  }
231  void setEmulation(bool _emul);
232  bool getEmulation(void);
233  int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
234  int parseAsciiDatagram(char* datagram, size_t datagram_length, sick_scan_msg::RadarScan *msgPtr, std::vector<SickScanRadarObject> &objectList, std::vector<SickScanRadarRawTarget> &rawTargetList); /* , SickScanConfig &config, */ // sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask);
235  void simulateAsciiDatagram(unsigned char * receiveBuffer, int* actual_length);
236  private:
237 // SickScanCommon *commonPtr;
238  void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern);
239  bool emul;
240  };
241 #endif
242 
243 } /* namespace sick_scan_xd */
244 #endif // SICK_GENERIC_RADAR_H_
sick_scan_xd::NO_RADAR
@ NO_RADAR
Definition: sick_generic_parser.h:104
sick_scan_xd::SickScanRadarSingleton::setNameOfRadar
void setNameOfRadar(const std::string &_radarName, RADAR_TYPE_ENUM _radarType)
Definition: sick_generic_radar.h:211
sick_scan_xd::SickScanRadarSingleton::m_range_filter
sick_scan_xd::SickRangeFilter m_range_filter
Definition: sick_generic_radar.h:192
sick_cloud_transform.h
sick_scan_xd::SickScanRadarRawTarget::vrad
float vrad
Definition: sick_generic_radar.h:116
sick_scan_xd::SickScanRadarRawTarget::Azimuth
float Azimuth() const
Definition: sick_generic_radar.h:89
sick_scan_xd::SickScanRadarSingleton::emul
bool emul
Definition: sick_generic_radar.h:181
sick_scan_xd::SickScanRadarSingleton::radarScan_pub_
rosPublisher< sick_scan_msg::RadarScan > radarScan_pub_
Definition: sick_generic_radar.h:189
sick_scan_xd::SickScanRadarObject
Definition: sick_generic_radar.h:121
sick_scan_xd::SickScanRadarSingleton::node
rosNodePtr node
Definition: sick_generic_radar.h:185
sick_scan_xd::SickCloudTransform
Definition: sick_cloud_transform.h:85
sick_scan_xd::SickScanRadarObject::v3Dx
float v3Dx
Definition: sick_generic_radar.h:163
sick_scan_xd::SickScanRadarObject::P3Dy
float P3Dy() const
Definition: sick_generic_radar.h:130
sick_scan_xd::SickScanRadarRawTarget::Vrad
float Vrad() const
Definition: sick_generic_radar.h:95
sick_scan_xd::SickScanRadarSingleton::instance
static SickScanRadarSingleton * instance
Definition: sick_generic_radar.h:174
sick_scan_xd::SickScanRadarObject::ObjId
int ObjId() const
Definition: sick_generic_radar.h:154
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_range_filter.h
sick_scan_xd::SickScanRadarRawTarget::azimuth
float azimuth
Definition: sick_generic_radar.h:115
sick_ros_wrapper.h
sick_scan_xd::SickScanRadarSingleton::getEmulation
bool getEmulation(void)
Definition: sick_generic_radar.cpp:311
sick_scan_xd::SickScanRadarRawTarget::Ampl
float Ampl() const
Definition: sick_generic_radar.h:101
sick_scan_xd::SickScanRadarSingleton::cloud_radar_rawtarget_pub_
rosPublisher< ros_sensor_msgs::PointCloud2 > cloud_radar_rawtarget_pub_
Definition: sick_generic_radar.h:187
sick_scan_xd::SickScanRadarSingleton::parseRadarDatagram
int parseRadarDatagram(char *datagram, size_t datagram_length, bool useBinaryProtocol, sick_scan_msg::RadarScan *msgPtr, std::vector< SickScanRadarObject > &objectList, std::vector< SickScanRadarRawTarget > &rawTargetList, int verboseLevel=0)
Parsing Ascii datagram.
Definition: sick_generic_radar.cpp:612
sick_scan_xd::SickScanRadarObject::ObjLength
void ObjLength(float val)
Definition: sick_generic_radar.h:151
sick_generic_parser.h
rosPublisher< ros_sensor_msgs::PointCloud2 >
sick_scan_xd::SickScanRadarObject::V3Dy
void V3Dy(float val)
Definition: sick_generic_radar.h:145
sick_scan_xd::SickScanRadarRawTarget::Dist
float Dist() const
Definition: sick_generic_radar.h:83
sick_scan_xd::SickScanRadarSingleton::parseDatagram
int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
Definition: sick_generic_radar.cpp:1472
sick_scan_xd::SickScanRadarRawTarget::ampl
float ampl
Definition: sick_generic_radar.h:117
sick_scan_xd::SickScanRadarObject::P3Dx
float P3Dx() const
Definition: sick_generic_radar.h:124
sick_scan_xd::SickScanRadarSingleton::m_add_transform_xyz_rpy
sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy
Definition: sick_generic_radar.h:191
ros::NodeHandle
sick_scan_xd::SickScanRadarRawTarget::Azimuth
void Azimuth(float val)
Definition: sick_generic_radar.h:92
sick_scan_xd::SickScanRadarSingleton::getInstance
static SickScanRadarSingleton * getInstance(rosNodePtr nh)
Definition: sick_generic_radar.cpp:88
sick_scan_xd::SickScanRadarObject::P3Dy
void P3Dy(float val)
Definition: sick_generic_radar.h:133
sick_scan_xd::SickScanRadarObject::p3Dy
float p3Dy
Definition: sick_generic_radar.h:162
sick_scan_xd::SickScanRadarObject::P3Dx
void P3Dx(float val)
Definition: sick_generic_radar.h:127
sick_scan_xd::SickScanRadarSingleton::getNameOfRadar
std::string getNameOfRadar()
Definition: sick_generic_radar.h:216
sick_scan_xd::SickScanRadarRawTarget::Mode
void Mode(int val)
Definition: sick_generic_radar.h:110
sick_scan_xd::SickScanRadarObject::ObjId
void ObjId(int val)
Definition: sick_generic_radar.h:157
sick_scan_xd::SickScanRadarObject::ObjLength
float ObjLength() const
Definition: sick_generic_radar.h:148
ros::Time
sick_scan_xd::SickScanRadarRawTarget::mode
int mode
Definition: sick_generic_radar.h:118
sick_scan_xd::SickScanRadarSingleton::simulateAsciiDatagram
void simulateAsciiDatagram(unsigned char *receiveBuffer, int *actual_length)
Definition: sick_generic_radar.cpp:1106
sick_scan_xd::SickScanRadarSingleton::simulateAsciiDatagramFromFile
void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern)
Definition: sick_generic_radar.cpp:1406
sick_scan_xd::RADAR_TYPE_ENUM
RADAR_TYPE_ENUM
Definition: sick_generic_parser.h:102
sick_scan_xd::SickScanRadarObject::V3Dy
float V3Dy() const
Definition: sick_generic_radar.h:142
sick_scan_xd::SickScanRadarRawTarget
Definition: sick_generic_radar.h:80
sick_scan_xd::SickScanRadarRawTarget::Dist
void Dist(float val)
Definition: sick_generic_radar.h:86
sick_scan_xd::SickScanRadarSingleton::setEmulation
void setEmulation(bool _emul)
Definition: sick_generic_radar.cpp:306
sick_scan_xd::SickScanRadarSingleton::radarName
std::string radarName
Definition: sick_generic_radar.h:183
sick_scan_xd::SickScanRadarRawTarget::Ampl
void Ampl(float val)
Definition: sick_generic_radar.h:104
sick_scan_base.h
sick_scan_xd::SickScanRadarRawTarget::Vrad
void Vrad(float val)
Definition: sick_generic_radar.h:98
sick_scan_common_nw.h
sick_scan_xd::RadarScan
::sick_scan_xd::RadarScan_< std::allocator< void > > RadarScan
Definition: RadarScan.h:68
sick_scan_xd::SickScanRadarObject::objId
int objId
Definition: sick_generic_radar.h:166
roswrap::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:317
sick_scan_xd::SickScanRadarSingleton::radarType
RADAR_TYPE_ENUM radarType
Definition: sick_generic_radar.h:184
sick_scan_xd::SickScanRadarObject::v3Dy
float v3Dy
Definition: sick_generic_radar.h:164
sick_scan_xd::SickScanRadarRawTarget::Mode
int Mode() const
Definition: sick_generic_radar.h:107
sick_scan_xd::SickScanRadarRawTarget::dist
float dist
Definition: sick_generic_radar.h:114
sick_scan_xd::SickScanRadarSingleton::SickScanRadarSingleton
SickScanRadarSingleton(rosNodePtr nh)
Definition: sick_generic_radar.cpp:98
sick_scan_xd::SickScanRadarSingleton::cloud_radar_track_pub_
rosPublisher< ros_sensor_msgs::PointCloud2 > cloud_radar_track_pub_
Definition: sick_generic_radar.h:188
sick_scan_xd::SickScanRadarObject::V3Dx
void V3Dx(float val)
Definition: sick_generic_radar.h:139
sick_scan_xd::SickScanRadarObject::p3Dx
float p3Dx
Definition: sick_generic_radar.h:161
sick_scan_xd::SickScanRadarSingleton
Definition: sick_generic_radar.h:170
sick_scan_xd::SickScanRadarObject::V3Dx
float V3Dx() const
Definition: sick_generic_radar.h:136
sick_scan_xd::SickRangeFilter
Definition: sick_range_filter.h:85
sick_scan_xd::SickScanRadarObject::objLength
float objLength
Definition: sick_generic_radar.h:165


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