sick_generic_imu.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 // Created by michael on 10/4/18.
4 //
5 
6 #ifndef SICK_SCAN_SICK_GENERIC_IMU_H
7 #define SICK_SCAN_SICK_GENERIC_IMU_H
8 
9 /*
10  * Copyright (C) 2018, Ing.-Buero Dr. Michael Lehning, Hildesheim
11  * Copyright (C) 2018, SICK AG, Waldkirch
12  * All rights reserved.
13  *
14 * Licensed under the Apache License, Version 2.0 (the "License");
15 * you may not use this file except in compliance with the License.
16 * You may obtain a copy of the License at
17 *
18 * http://www.apache.org/licenses/LICENSE-2.0
19 *
20 * Unless required by applicable law or agreed to in writing, software
21 * distributed under the License is distributed on an "AS IS" BASIS,
22 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 * See the License for the specific language governing permissions and
24 * limitations under the License.
25 *
26 *
27 * All rights reserved.
28 *
29 * Redistribution and use in source and binary forms, with or without
30 * modification, are permitted provided that the following conditions are met:
31 *
32 * * Redistributions of source code must retain the above copyright
33 * notice, this list of conditions and the following disclaimer.
34 * * Redistributions in binary form must reproduce the above copyright
35 * notice, this list of conditions and the following disclaimer in the
36 * documentation and/or other materials provided with the distribution.
37 * * Neither the name of Osnabrueck University nor the names of its
38 * contributors may be used to endorse or promote products derived from
39 * this software without specific prior written permission.
40 * * Neither the name of SICK AG nor the names of its
41 * contributors may be used to endorse or promote products derived from
42 * this software without specific prior written permission
43 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
44 * contributors may be used to endorse or promote products derived from
45 * this software without specific prior written permission
46 *
47 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
48 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
49 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
50 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
51 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
52 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
53 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
54 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
55 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
56 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
57 * POSSIBILITY OF SUCH DAMAGE.
58  *
59  * Created on: 28th May 2018
60  *
61  * Authors:
62  * Michael Lehning <michael.lehning@lehning.de>
63  *
64  */
65 
66 #include <stdio.h>
67 #include <stdlib.h>
68 #include <string>
69 #include <string.h>
70 #include <vector>
71 
74 
77 #include "softwarePLL.h"
78 
79 namespace sick_scan_xd
80 {
81 
82 
84  {
85  public:
86  UINT64 TimeStamp() const
87  { return timeStamp; }
88 
89  void TimeStamp(UINT64 val)
90  { timeStamp = (UINT32)val; }
91 
92  float QuaternionX() const
93  { return quaternionX; }
94 
95  void QuaternionX(float val)
96  { quaternionX = val; }
97 
98  float QuaternionY() const
99  { return quaternionY; }
100 
101  void QuaternionY(float val)
102  { quaternionY = val; }
103 
104  float QuaternionZ() const
105  { return quaternionZ; }
106 
107  void QuaternionZ(float val)
108  { quaternionZ = val; }
109 
110  float QuaternionW() const
111  { return quaternionW; }
112 
113  void QuaternionW(float val)
114  { quaternionW = val; }
115 
116  float QuaternionAccuracy() const
117  { return quaternionAccuracy; }
118 
119  void QuaternionAccuracy(float val)
120  { quaternionAccuracy = val; }
121 
122 
123  float AngularVelocityX() const
124  { return velocityX; }
125 
126  void AngularVelocityX(float val)
127  { velocityX = val; }
128 
129  float AngularVelocityY() const
130  { return velocityY; }
131 
132  void AngularVelocityY(float val)
133  { velocityY = val; }
134 
135  float AngularVelocityZ() const
136  { return velocityZ; }
137 
138  void AngularVelocityZ(float val)
139  { velocityZ = val; }
140 
142  { return velocityReliability; }
143 
145  { velocityReliability = val; }
146 
147  float LinearAccelerationX() const
148  { return linearAccelerationX; }
149 
150  void LinearAccelerationX(float val)
151  { linearAccelerationX = val; }
152 
153  float LinearAccelerationY() const
154  { return linearAccelerationY; }
155 
156  void LinearAccelerationY(float val)
157  { linearAccelerationY = val; }
158 
159  float LinearAccelerationZ() const
160  { return linearAccelerationZ; }
161 
162  void LinearAccelerationZ(float val)
163  { linearAccelerationZ = val; }
164 
167 
170 
171  private:
173  float quaternionX;
174  float quaternionY;
175  float quaternionZ;
176  float quaternionW;
178  float velocityX;
179  float velocityY;
180  float velocityZ;
186 
187  };
188 
190  {
191  public:
193  {
194  commonPtr = commonPtr_;
195  nh = nh_;
196  }
197 
198  bool isImuDatagram(char *datagram, size_t datagram_length);
199 
200  bool isImuBinaryDatagram(char *datagram, size_t datagram_length);
201 
202  bool isImuAsciiDatagram(char *datagram, size_t datagram_length);
203 
204  bool isImuAckDatagram(char *datagram, size_t datagram_length);
205 
206  int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
207 
208  int parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
209 
210  int parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
211 
212  static void imuParserTest();
213 
214  static void quaternion2rpyTest(); // test for converting quaternion to rpy
215 
216  double simpleFmodTwoPi(double angle);
217 
218  private:
221  bool emul;
222  };
223 
224 } /* namespace sick_scan_xd */
225 
226 
227 #endif //SICK_SCAN_SICK_GENERIC_IMU_H
sick_scan_xd::SickScanImuValue::velocityX
float velocityX
Definition: sick_generic_imu.h:178
UINT16
uint16_t UINT16
Definition: BasicDatatypes.hpp:73
sick_scan_xd::SickScanImuValue::LinearAccelerationZ
void LinearAccelerationZ(float val)
Definition: sick_generic_imu.h:162
sick_scan_xd::SickScanImuValue::linearAccelerationX
float linearAccelerationX
Definition: sick_generic_imu.h:182
sick_scan_xd::SickScanImuValue::QuaternionX
void QuaternionX(float val)
Definition: sick_generic_imu.h:95
sick_scan_xd::SickScanImuValue::QuaternionAccuracy
float QuaternionAccuracy() const
Definition: sick_generic_imu.h:116
sick_scan_xd::SickScanImuValue::AngularVelocityReliability
void AngularVelocityReliability(UINT16 val)
Definition: sick_generic_imu.h:144
sick_scan_xd::SickScanImuValue::quaternionZ
float quaternionZ
Definition: sick_generic_imu.h:175
sick_scan_xd::SickScanCommon
Definition: sick_scan_common.h:102
sick_scan_xd::SickScanImuValue::linearAccelerationReliability
UINT16 linearAccelerationReliability
Definition: sick_generic_imu.h:185
sick_scan_xd::SickScanImuValue::LinearAccelerationX
void LinearAccelerationX(float val)
Definition: sick_generic_imu.h:150
sick_scan_xd::SickScanImu::commonPtr
SickScanCommon * commonPtr
Definition: sick_generic_imu.h:219
sick_scan_xd::SickScanImuValue::AngularVelocityY
float AngularVelocityY() const
Definition: sick_generic_imu.h:129
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_xd::SickScanImuValue::timeStamp
UINT32 timeStamp
Definition: sick_generic_imu.h:172
sick_ros_wrapper.h
sick_scan_xd::SickScanImuValue::quaternionW
float quaternionW
Definition: sick_generic_imu.h:176
sick_scan_xd::SickScanImu::isImuDatagram
bool isImuDatagram(char *datagram, size_t datagram_length)
Definition: sick_generic_imu.cpp:91
sick_scan_xd::SickScanImu::isImuAsciiDatagram
bool isImuAsciiDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
Definition: sick_generic_imu.cpp:272
sick_scan_xd::SickScanImuValue::LinearAccelerationY
float LinearAccelerationY() const
Definition: sick_generic_imu.h:153
sick_scan_xd::SickScanImu::simpleFmodTwoPi
double simpleFmodTwoPi(double angle)
Checking angle to be in the interval [-M_PI,M_PI] Of course you can also use fmod,...
Definition: sick_generic_imu.cpp:123
sick_scan_xd::SickScanImu::emul
bool emul
Definition: sick_generic_imu.h:221
sick_scan_xd::SickScanImuValue::AngularVelocityX
void AngularVelocityX(float val)
Definition: sick_generic_imu.h:126
softwarePLL.h
sick_generic_parser.h
sick_scan_xd::SickScanImuValue::linearAccelerationZ
float linearAccelerationZ
Definition: sick_generic_imu.h:184
sick_scan_xd::SickScanImu::parseBinaryDatagram
int parseBinaryDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
Definition: sick_generic_imu.cpp:203
sick_scan_xd::SickScanImuValue::QuaternionZ
void QuaternionZ(float val)
Definition: sick_generic_imu.h:107
UINT64
uint64_t UINT64
Definition: BasicDatatypes.hpp:70
sick_scan_xd::SickScanImuValue::LinearAccelerationReliability
void LinearAccelerationReliability(UINT16 val)
Definition: sick_generic_imu.h:168
sick_scan_xd::SickScanImu::quaternion2rpyTest
static void quaternion2rpyTest()
Test barebone implemetation from quaternio to euler (Roll-Pitch-Yaw-Sequence) to avoid problems using...
Definition: sick_generic_imu.cpp:434
sick_scan_xd::SickScanImuValue::QuaternionY
void QuaternionY(float val)
Definition: sick_generic_imu.h:101
sick_scan_xd::SickScanImuValue::quaternionY
float quaternionY
Definition: sick_generic_imu.h:174
sick_scan_xd::SickScanImuValue::velocityZ
float velocityZ
Definition: sick_generic_imu.h:180
sick_scan_xd::SickScanImuValue::QuaternionY
float QuaternionY() const
Definition: sick_generic_imu.h:98
sick_scan_xd::SickScanImuValue::LinearAccelerationY
void LinearAccelerationY(float val)
Definition: sick_generic_imu.h:156
ros::NodeHandle
sick_scan_xd::SickScanImuValue::AngularVelocityX
float AngularVelocityX() const
Definition: sick_generic_imu.h:123
sick_scan_xd::SickScanImuValue::AngularVelocityReliability
UINT16 AngularVelocityReliability() const
Definition: sick_generic_imu.h:141
sick_scan_xd::SickScanImuValue::AngularVelocityZ
void AngularVelocityZ(float val)
Definition: sick_generic_imu.h:138
sick_scan_xd::SickScanImuValue::AngularVelocityY
void AngularVelocityY(float val)
Definition: sick_generic_imu.h:132
sick_scan_xd::SickScanImuValue::TimeStamp
void TimeStamp(UINT64 val)
Definition: sick_generic_imu.h:89
sick_scan_xd::SickScanImu::isImuAckDatagram
bool isImuAckDatagram(char *datagram, size_t datagram_length)
Definition: sick_generic_imu.cpp:136
sick_scan_xd::SickScanImu::isImuBinaryDatagram
bool isImuBinaryDatagram(char *datagram, size_t datagram_length)
Checking ASCII diagram for imu message type.
Definition: sick_generic_imu.cpp:166
sick_scan_xd::SickScanImu
Definition: sick_generic_imu.h:189
sick_scan_xd::SickScanImuValue::QuaternionAccuracy
void QuaternionAccuracy(float val)
Definition: sick_generic_imu.h:119
sick_scan_xd::SickScanImuValue::QuaternionW
void QuaternionW(float val)
Definition: sick_generic_imu.h:113
sick_scan_xd::SickScanImuValue::LinearAccelerationZ
float LinearAccelerationZ() const
Definition: sick_generic_imu.h:159
sick_scan_xd::SickScanImuValue::linearAccelerationY
float linearAccelerationY
Definition: sick_generic_imu.h:183
sick_scan_xd::SickScanImuValue::TimeStamp
UINT64 TimeStamp() const
Definition: sick_generic_imu.h:86
ros::Time
sick_scan_xd::SickScanImuValue::QuaternionW
float QuaternionW() const
Definition: sick_generic_imu.h:110
sick_scan_xd::SickScanImuValue::quaternionAccuracy
float quaternionAccuracy
Definition: sick_generic_imu.h:177
sick_scan_xd::SickScanImuValue::velocityY
float velocityY
Definition: sick_generic_imu.h:179
sick_scan_base.h
sick_scan_common_nw.h
UINT32
uint32_t UINT32
Definition: BasicDatatypes.hpp:72
sick_scan_xd::SickScanImuValue::QuaternionX
float QuaternionX() const
Definition: sick_generic_imu.h:92
roswrap::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:317
sick_scan_xd::SickScanImuValue::LinearAccelerationX
float LinearAccelerationX() const
Definition: sick_generic_imu.h:147
sick_scan_xd::SickScanImu::SickScanImu
SickScanImu(SickScanCommon *commonPtr_, rosNodePtr nh_)
Definition: sick_generic_imu.h:192
sick_scan_xd::SickScanImu::imuParserTest
static void imuParserTest()
Definition: sick_generic_imu.cpp:497
sick_scan_xd::SickScanImu::nh
rosNodePtr nh
Definition: sick_generic_imu.h:220
sick_scan_xd::SickScanImuValue
Definition: sick_generic_imu.h:83
sick_scan_xd::SickScanImu::parseDatagram
int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
Definition: sick_generic_imu.cpp:554
sick_scan_xd::SickScanImuValue::velocityReliability
UINT16 velocityReliability
Definition: sick_generic_imu.h:181
sick_scan_xd::SickScanImu::parseAsciiDatagram
int parseAsciiDatagram(char *datagram, size_t datagram_length, SickScanImuValue *imValuePtr)
Parsing Ascii datagram.
Definition: sick_generic_imu.cpp:299
sick_scan_xd::SickScanImuValue::LinearAccelerationReliability
UINT16 LinearAccelerationReliability() const
Definition: sick_generic_imu.h:165
sick_scan_xd::SickScanImuValue::AngularVelocityZ
float AngularVelocityZ() const
Definition: sick_generic_imu.h:135
sick_scan_xd::SickScanImuValue::QuaternionZ
float QuaternionZ() const
Definition: sick_generic_imu.h:104
sick_scan_xd::SickScanImuValue::quaternionX
float quaternionX
Definition: sick_generic_imu.h:173


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