sick_generic_imu.h
Go to the documentation of this file.
1 //
2 // Created by michael on 10/4/18.
3 //
4 
5 #ifndef SICK_SCAN_SICK_GENERIC_IMU_H
6 #define SICK_SCAN_SICK_GENERIC_IMU_H
7 
8 /*
9  * Copyright (C) 2018, Ing.-Buero Dr. Michael Lehning, Hildesheim
10  * Copyright (C) 2018, SICK AG, Waldkirch
11  * All rights reserved.
12  *
13  * Redistribution and use in source and binary forms, with or without
14  * modification, are permitted provided that the following conditions are met:
15  *
16  * * Redistributions of source code must retain the above copyright
17  * notice, this list of conditions and the following disclaimer.
18  * * Redistributions in binary form must reproduce the above copyright
19  * notice, this list of conditions and the following disclaimer in the
20  * documentation and/or other materials provided with the distribution.
21  * * Neither the name of Osnabrück University nor the names of its
22  * contributors may be used to endorse or promote products derived from
23  * this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
26  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
27  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
28  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
29  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
30  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
31  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
32  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
33  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
34  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * Created on: 28th May 2018
38  *
39  * Authors:
40  * Michael Lehning <michael.lehning@lehning.de>
41  *
42  */
43 
44 #include <stdio.h>
45 #include <stdlib.h>
46 #include <string>
47 #include <string.h>
48 #include <vector>
49 
50 #include <ros/ros.h>
51 #include <sensor_msgs/LaserScan.h>
52 #include <sensor_msgs/PointCloud.h>
53 #include <sensor_msgs/PointCloud2.h>
54 #include <std_msgs/String.h>
55 
59 #include <sick_scan/RadarScan.h> // generated by msg-generator
60 
61 #ifndef _MSC_VER
62 #include <dynamic_reconfigure/server.h>
63 #include <sick_scan/SickScanConfig.h>
64 #endif
67 #include <ros/ros.h>
68 #include <sensor_msgs/Imu.h>
69 #include "softwarePLL.h"
70 namespace sick_scan
71  {
72 
73 
75  {
76  public:
77  UINT64 TimeStamp() const { return timeStamp; }
78  void TimeStamp(UINT64 val) { timeStamp = val; }
79  float QuaternionX() const { return quaternionX; }
80  void QuaternionX(float val) { quaternionX = val; }
81  float QuaternionY() const { return quaternionY; }
82  void QuaternionY(float val) { quaternionY = val; }
83  float QuaternionZ() const { return quaternionZ; }
84  void QuaternionZ(float val) { quaternionZ = val; }
85  float QuaternionW() const { return quaternionW; }
86  void QuaternionW(float val) { quaternionW = val; }
87 
88  float QuaternionAccuracy() const { return quaternionAccuracy; }
89  void QuaternionAccuracy(float val) { quaternionAccuracy = val; }
90 
91 
92  float AngularVelocityX() const { return velocityX; }
93  void AngularVelocityX(float val) { velocityX = val; }
94  float AngularVelocityY() const { return velocityY; }
95  void AngularVelocityY(float val) { velocityY = val; }
96  float AngularVelocityZ() const { return velocityZ; }
97  void AngularVelocityZ(float val) { velocityZ = val; }
98 
101 
102  float LinearAccelerationX() const { return linearAccelerationX; }
103  void LinearAccelerationX(float val) { linearAccelerationX = val; }
104  float LinearAccelerationY() const { return linearAccelerationY; }
105  void LinearAccelerationY(float val) { linearAccelerationY = val; }
106  float LinearAccelerationZ() const { return linearAccelerationZ; }
107  void LinearAccelerationZ(float val) { linearAccelerationZ = val; }
108 
111 
112  private:
114  float quaternionX;
115  float quaternionY;
116  float quaternionZ;
117  float quaternionW;
119  float velocityX;
120  float velocityY;
121  float velocityZ;
127 
128  };
129 
131  {
132  public:
134  {
135  commonPtr = commonPtr_;
136  }
137  bool isImuDatagram(char *datagram, size_t datagram_length);
138  bool isImuBinaryDatagram(char *datagram, size_t datagram_length);
139  bool isImuAsciiDatagram(char *datagram, size_t datagram_length);
140  bool isImuAckDatagram(char *datagram, size_t datagram_length);
141 
142  int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
143  int parseAsciiDatagram(char* datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
144  int parseBinaryDatagram(char* datagram, size_t datagram_length, SickScanImuValue *imValuePtr);
145  static void imuParserTest();
146  double simpleFmodTwoPi(double angle);
147 
148  private:
150  bool emul;
151  };
152 
153  } /* namespace sick_scan */
154 
155 
156 #endif //SICK_SCAN_SICK_GENERIC_IMU_H
UINT16 LinearAccelerationReliability() const
uint16_t UINT16
void LinearAccelerationReliability(UINT16 val)
uint32_t UINT32
SickScanCommon * commonPtr
void LinearAccelerationX(float val)
void AngularVelocityY(float val)
void QuaternionAccuracy(float val)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void LinearAccelerationY(float val)
void LinearAccelerationZ(float val)
void AngularVelocityReliability(UINT16 val)
void AngularVelocityX(float val)
void AngularVelocityZ(float val)
UINT16 AngularVelocityReliability() const
uint64_t UINT64
SickScanImu(SickScanCommon *commonPtr_)


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 04:55:32