sick_generic_field_mon.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_FIELD_MON_H_
60 #define SICK_GENERIC_FIELD_MON_H_
61 
62 #include <stdio.h>
63 #include <stdlib.h>
64 #include <string>
65 #include <string.h>
66 #include <vector>
67 
69 
70 namespace sick_scan_xd
71 {
73  {
74  MON_FIELD_RADIAL = 0, // not supported
78  };
79 
81  {
82  public:
83  /*
84  ** @brief Converts a point of a segmented field to carthesian coordinates
85  ** @param[in] range range in meter
86  ** @param[in] angle_rad angle in radians
87  ** @param[out] x x in meter in ros coordinate system
88  ** @param[out] y y in meter in ros coordinate system
89  */
90  static void segmentedFieldPointToCarthesian(float range, float angle_rad, float& x, float& y);
91 
92  /*
93  ** @brief Converts a rectangular field to carthesian coordinates, i.e. to 4 corner points carthesian (ros) coordinates
94  ** @param[in] distRefPointMeter range of ref point (rect center) in meter
95  ** @param[in] angleRefPointRad angle of ref point (rect center) in radians
96  ** @param[in] rotAngleRad rotation of rectangle in radians
97  ** @param[in] rectWidthMeter width of rectangle in meter
98  ** @param[in] rectLengthMeter width of rectangle in meter
99  ** @param[out] points_x x of corner points in meter in ros coordinate system
100  ** @param[out] points_y y of corner points in meter in ros coordinate system
101  */
102  static void rectangularFieldToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float points_x[4], float points_y[4]);
103 
104  /*
105  ** @brief Converts a dynamic field to carthesian coordinates. The dynamic field is just converted into 2 rectangular fields,
106  ** each rectangular field described by to 4 corner points carthesian (ros) coordinates.
107  ** The first rectangular field has size rectWidthMeter x maxLengthMeter, the second rectangular field has size rectWidthMeter x rectLengthMeter.
108  ** The rectangular fields are returned by 4 corner points (points_x[n], points_y[n]) with 0 <= n < 4 for the first (big) rectangle and 4 <= n < 8 for the second (smaller) rectangle.
109  ** @param[in] distRefPointMeter range of ref point (rect center) in meter
110  ** @param[in] angleRefPointRad angle of ref point (rect center) in radians
111  ** @param[in] rotAngleRad rotation of rectangle in radians
112  ** @param[in] rectWidthMeter width of rectangle in meter
113  ** @param[in] rectLengthMeter width of rectangle in meter at v = 0
114  ** @param[in] maxSpeedMeterPerSec max speed (unused)
115  ** @param[in] maxLengthMeter width of rectangle in meter at v = max. speed
116  ** @param[out] points_x x of corner points in meter in ros coordinate system
117  ** @param[out] points_y y of corner points in meter in ros coordinate system
118  */
119  static void dynamicFieldPointToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float maxSpeedMeterPerSec, float maxLengthMeter, float points_x[8], float points_y[8]);
120 
121  };
122 
124  {
125  public:
126 
128  const SickScanMonFieldType& fieldType(void) const { return m_fieldType; }
129 
130  void pushFieldPointCarthesian(float x, float y)
131  {
132  m_fieldPoints_X.push_back(x);
133  m_fieldPoints_Y.push_back(y);
134  }
135 
136  int getPointCount(void) const
137  {
138  assert(m_fieldPoints_X.size() == m_fieldPoints_Y.size());
139  return (int)m_fieldPoints_X.size();
140  }
141 
142  const std::vector<float>& getFieldPointsX(void) const { return m_fieldPoints_X; }
143  const std::vector<float>& getFieldPointsY(void) const { return m_fieldPoints_Y; }
144 
145  private:
147  std::vector<float> m_fieldPoints_X;
148  std::vector<float> m_fieldPoints_Y;
149  };
150 
151 
153  {
154  private:
155  /* Here will be the instance stored. */
157 
158  /* Private constructor to prevent instancing. */
160 
161  std::vector<SickScanMonField>monFields;
163  int mon_field_selection_method = 0; // FieldSetSelectionMethod: 0 = digital inputs (default), 1 = telegram "sWN ActiveFieldSet"
164 
165  public:
166  /* Static access method. */
168 
169  const std::vector<SickScanMonField>& getMonFields(void) const { return monFields; }
170 
171  void setActiveFieldset(int active_fieldset) { active_mon_fieldset = active_fieldset; }
173 
174  void setFieldSelectionMethod(int field_selection_method) { mon_field_selection_method = field_selection_method; } // FieldSetSelectionMethod: 0 = digital inputs (default), 1 = telegram "sWN ActiveFieldSet"
176 
177  int parseAsciiLIDinputstateMsg(unsigned char* datagram, int datagram_length);
178  int parseBinaryLIDinputstateMsg(unsigned char* datagram, int datagram_length, sick_scan_msg::LIDinputstateMsg& inputstate_msg);
179 
180  void parseActiveFieldSetResponse(unsigned char* datagram, int datagram_length, uint16_t* active_field_set);
181  void parseFieldSetSelectionMethodResponse(unsigned char* datagram, int datagram_length, uint8_t* field_set_selection_method);
182 
183  int parseBinaryDatagram(std::vector<unsigned char> datagramm, float rectFieldAngleRefPointOffsetRad);
184 
185  int parseAsciiDatagram(std::vector<unsigned char> datagramm, float rectFieldAngleRefPointOffsetRad);
186 
187  std::string LIDinputstateMsgToString(const sick_scan_msg::LIDinputstateMsg& inputstate_msg);
188  };
189 
190 
191 #if 0
192  class SickScanRadar
193  {
194  public:
195  SickScanRadar(SickScanCommon *commonPtr_)
196  {
197  commonPtr = commonPtr_;
198  }
199  void setEmulation(bool _emul);
200  bool getEmulation(void);
201  int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
202  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);
203  void simulateAsciiDatagram(unsigned char * receiveBuffer, int* actual_length);
204  private:
205 // SickScanCommon *commonPtr;
206  void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern);
207  bool emul;
208  };
209 #endif
210 
211 } /* namespace sick_scan_xd */
212 #endif // SICK_GENERIC_RADAR_H_
sick_scan_xd::SickScanMonField::pushFieldPointCarthesian
void pushFieldPointCarthesian(float x, float y)
Definition: sick_generic_field_mon.h:130
sick_scan_xd::MON_FIELD_RECTANGLE
@ MON_FIELD_RECTANGLE
Definition: sick_generic_field_mon.h:75
sick_scan_xd::SickScanFieldMonSingleton::parseAsciiLIDinputstateMsg
int parseAsciiLIDinputstateMsg(unsigned char *datagram, int datagram_length)
Parse binary LIDinputstate message and set active field set.
Definition: sick_generic_field_mon.cpp:175
sick_scan_xd::SickScanFieldMonSingleton::setActiveFieldset
void setActiveFieldset(int active_fieldset)
Definition: sick_generic_field_mon.h:171
sick_scan_xd::SickScanFieldMonSingleton::LIDinputstateMsgToString
std::string LIDinputstateMsgToString(const sick_scan_msg::LIDinputstateMsg &inputstate_msg)
Converts a LIDinputstateMsg to a readable string.
Definition: sick_generic_field_mon.cpp:285
sick_scan_xd::SickScanMonField::getPointCount
int getPointCount(void) const
Definition: sick_generic_field_mon.h:136
sick_scan_xd::MON_FIELD_SEGMENTED
@ MON_FIELD_SEGMENTED
Definition: sick_generic_field_mon.h:76
sick_scan_xd::MON_FIELD_RADIAL
@ MON_FIELD_RADIAL
Definition: sick_generic_field_mon.h:74
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_xd::SickScanFieldMonSingleton::parseBinaryLIDinputstateMsg
int parseBinaryLIDinputstateMsg(unsigned char *datagram, int datagram_length, sick_scan_msg::LIDinputstateMsg &inputstate_msg)
Parse binary LIDinputstate message and set active field set.
Definition: sick_generic_field_mon.cpp:187
sick_ros_wrapper.h
sick_scan_xd::SickScanMonFieldConverter::segmentedFieldPointToCarthesian
static void segmentedFieldPointToCarthesian(float range, float angle_rad, float &x, float &y)
Definition: sick_generic_field_mon.cpp:74
sick_scan_xd::SickScanFieldMonSingleton::parseFieldSetSelectionMethodResponse
void parseFieldSetSelectionMethodResponse(unsigned char *datagram, int datagram_length, uint8_t *field_set_selection_method)
Parse binary FieldSetSelectionMethod response "sRA FieldSetSelectionMethod".
Definition: sick_generic_field_mon.cpp:274
sick_scan_xd::SickScanFieldMonSingleton::parseActiveFieldSetResponse
void parseActiveFieldSetResponse(unsigned char *datagram, int datagram_length, uint16_t *active_field_set)
Parse binary ActiveFieldSet response "sRA ActiveFieldSet".
Definition: sick_generic_field_mon.cpp:260
sick_scan_xd::SickScanMonFieldConverter::rectangularFieldToCarthesian
static void rectangularFieldToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float points_x[4], float points_y[4])
Definition: sick_generic_field_mon.cpp:90
sick_scan_xd::SickScanFieldMonSingleton::getInstance
static SickScanFieldMonSingleton * getInstance()
Definition: sick_generic_field_mon.cpp:155
sick_scan_xd::SickScanFieldMonSingleton::active_mon_fieldset
int active_mon_fieldset
Definition: sick_generic_field_mon.h:162
sick_scan_xd::SickScanMonField::getFieldPointsX
const std::vector< float > & getFieldPointsX(void) const
Definition: sick_generic_field_mon.h:142
sick_scan_xd::SickScanMonFieldConverter
Definition: sick_generic_field_mon.h:80
sick_scan_xd::SickScanFieldMonSingleton::parseAsciiDatagram
int parseAsciiDatagram(std::vector< unsigned char > datagramm, float rectFieldAngleRefPointOffsetRad)
Parsing Ascii datagram.
Definition: sick_generic_field_mon.cpp:303
sick_scan_xd::SickScanMonFieldType
SickScanMonFieldType
Definition: sick_generic_field_mon.h:72
sick_scan_xd::SickScanMonField::getFieldPointsY
const std::vector< float > & getFieldPointsY(void) const
Definition: sick_generic_field_mon.h:143
sick_scan_xd::MON_FIELD_DYNAMIC
@ MON_FIELD_DYNAMIC
Definition: sick_generic_field_mon.h:77
sick_scan_xd::SickScanMonFieldConverter::dynamicFieldPointToCarthesian
static void dynamicFieldPointToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float maxSpeedMeterPerSec, float maxLengthMeter, float points_x[8], float points_y[8])
Definition: sick_generic_field_mon.cpp:137
sick_scan_xd::LIDinputstateMsg
::sick_scan_xd::LIDinputstateMsg_< std::allocator< void > > LIDinputstateMsg
Definition: LIDinputstateMsg.h:110
ros::Time
sick_scan_xd::SickScanMonField
Definition: sick_generic_field_mon.h:123
sick_scan_xd::SickScanMonField::m_fieldType
SickScanMonFieldType m_fieldType
Definition: sick_generic_field_mon.h:146
sick_scan_xd::SickScanFieldMonSingleton::parseBinaryDatagram
int parseBinaryDatagram(std::vector< unsigned char > datagramm, float rectFieldAngleRefPointOffsetRad)
Definition: sick_generic_field_mon.cpp:310
sick_scan_xd::SickScanFieldMonSingleton::getMonFields
const std::vector< SickScanMonField > & getMonFields(void) const
Definition: sick_generic_field_mon.h:169
sick_scan_xd::SickScanMonField::fieldType
const SickScanMonFieldType & fieldType(void) const
Definition: sick_generic_field_mon.h:128
sick_scan_base.h
sick_scan_xd::SickScanFieldMonSingleton
Definition: sick_generic_field_mon.h:152
sick_scan_xd::SickScanMonField::m_fieldPoints_X
std::vector< float > m_fieldPoints_X
Definition: sick_generic_field_mon.h:147
sick_scan_xd::SickScanFieldMonSingleton::getFieldSelectionMethod
int getFieldSelectionMethod(void)
Definition: sick_generic_field_mon.h:175
sick_scan_xd::SickScanMonField::fieldType
SickScanMonFieldType & fieldType(void)
Definition: sick_generic_field_mon.h:127
sick_scan_xd::RadarScan
::sick_scan_xd::RadarScan_< std::allocator< void > > RadarScan
Definition: RadarScan.h:68
roswrap::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:317
sick_scan_xd::SickScanFieldMonSingleton::instance
static SickScanFieldMonSingleton * instance
Definition: sick_generic_field_mon.h:156
sick_scan_xd::SickScanFieldMonSingleton::getActiveFieldset
int getActiveFieldset(void)
Definition: sick_generic_field_mon.h:172
sick_scan_xd::SickScanFieldMonSingleton::SickScanFieldMonSingleton
SickScanFieldMonSingleton()
Definition: sick_generic_field_mon.cpp:165
sick_scan_xd::SickScanFieldMonSingleton::mon_field_selection_method
int mon_field_selection_method
Definition: sick_generic_field_mon.h:163
sick_scan_xd::SickScanFieldMonSingleton::setFieldSelectionMethod
void setFieldSelectionMethod(int field_selection_method)
Definition: sick_generic_field_mon.h:174
sick_scan_xd::SickScanMonField::m_fieldPoints_Y
std::vector< float > m_fieldPoints_Y
Definition: sick_generic_field_mon.h:148
sick_scan_xd::SickScanFieldMonSingleton::monFields
std::vector< SickScanMonField > monFields
Definition: sick_generic_field_mon.h:161


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