sick_nav_scandata_parser.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_parser parses 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_PARSER_H_
60 #define SICK_NAV_SCANDATA_PARSER_H_
61 
62 #include <string>
63 #include <vector>
64 
68 
69 namespace sick_scan_xd
70 {
74  bool parseNAV350BinaryPositionData(const uint8_t* receiveBuffer, int receiveBufferLength, NAV350mNPOSData& navdata);
75 
77  bool parseNAV350BinaryLandmarkData(const uint8_t* receiveBuffer, int& receivePos, int receiveBufferLength, NAV350LandmarkData& landmarkData);
78 
80  bool parseNAV350BinaryLandmarkDataDoMappingResponse(const uint8_t* receiveBuffer, int receiveBufferLength, NAV350LandmarkDataDoMappingResponse& landmarkData);
81 
83  std::vector<uint8_t> createNAV350BinaryAddLandmarkRequest(const NAV350LandmarkData& landmarkData, int nav_curr_layer);
84 
86  std::vector<uint8_t> createNAV350BinaryAddLandmarkRequest(const std::vector<sick_scan_xd::NAV350ImkLandmark> landmarks);
87 
90 
92  bool parseNAV350BinaryPositionData(const uint8_t* receiveBuffer, int receiveBufferLength, short& elevAngleX200, double& elevationAngleInRad, rosTime& recvTimeStamp,
93  bool config_sw_pll_only_publish, double config_time_offset, SickGenericParser* parser_, int& numEchos, ros_sensor_msgs::LaserScan & msg,
94  sick_scan_msg::NAVPoseData& nav_pose_msg, sick_scan_msg::NAVLandmarkData& nav_landmark_msg, NAV350mNPOSData& navdata);
95 
97  ros_geometry_msgs::TransformStamped convertNAVPoseDataToTransform(NAV350PoseData& poseData, rosTime recvTimeStamp, double config_time_offset,
98  const std::string& tf_parent_frame_id, const std::string& tf_child_frame_id, SickGenericParser* parser_);
99 
101  void rotateXYbyAngleOffset(float& x, float& y, double angle_offset);
102 
104  void convertNAVCartPos2DtoROSPos2D(int32_t nav_posx_mm, int32_t nav_posy_mm, float& ros_posx_m, float& ros_posy_m, double nav_angle_offset);
105 
107  void convertNAVCartPos3DtoROSPos3D(int32_t nav_posx_mm, int32_t nav_posy_mm, uint32_t nav_phi_mdeg, float& ros_posx_m, float& ros_posy_m, float& ros_yaw_rad, double nav_angle_offset);
108 
110  ros_visualization_msgs::MarkerArray convertNAVLandmarkDataToMarker(const std::vector<NAV350ReflectorData>& reflectors, ros_std_msgs::Header& header, SickGenericParser* parser_);
111 
113  std::vector<sick_scan_xd::NAV350ImkLandmark> readNAVIMKfile(const std::string& nav_imk_file);
114 
117 
118 } /* namespace sick_scan_xd */
119 #endif /* SICK_NAV_SCANDATA_PARSER_H_ */
sick_scan_xd::NAVLandmarkData
::sick_scan_xd::NAVLandmarkData_< std::allocator< void > > NAVLandmarkData
Definition: NAVLandmarkData.h:66
sick_scan_xd::convertNAVLandmarkDataToMarker
ros_visualization_msgs::MarkerArray convertNAVLandmarkDataToMarker(const std::vector< NAV350ReflectorData > &reflectors, ros_std_msgs::Header &header, SickGenericParser *parser_)
Definition: sick_nav_scandata_parser.cpp:839
sick_scan_xd::parseNAV350BinaryUnittest
bool parseNAV350BinaryUnittest()
Definition: sick_nav_scandata_parser.cpp:200
msg
msg
sick_scan_xd::NAVPoseData
::sick_scan_xd::NAVPoseData_< std::allocator< void > > NAVPoseData
Definition: NAVPoseData.h:120
geometry_msgs::TransformStamped
::geometry_msgs::TransformStamped_< std::allocator< void > > TransformStamped
Definition: TransformStamped.h:60
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_ros_wrapper.h
sick_nav_scandata.h
sensor_msgs::LaserScan
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
Definition: LaserScan.h:94
sick_scan_xd::parseNAV350BinaryLandmarkDataDoMappingResponse
bool parseNAV350BinaryLandmarkDataDoMappingResponse(const uint8_t *receiveBuffer, int receiveBufferLength, NAV350LandmarkDataDoMappingResponse &landmarkData)
Definition: sick_nav_scandata_parser.cpp:466
sick_generic_parser.h
sick_scan_xd::createNAV350BinarySetSpeedRequest
std::vector< uint8_t > createNAV350BinarySetSpeedRequest(const sick_scan_msg::NAVOdomVelocity &msg)
Definition: sick_nav_scandata_parser.cpp:552
visualization_msgs::MarkerArray
::visualization_msgs::MarkerArray_< std::allocator< void > > MarkerArray
Definition: MarkerArray.h:50
sick_scan_xd::rotateXYbyAngleOffset
void rotateXYbyAngleOffset(float &x, float &y, double angle_offset)
Definition: sick_nav_scandata_parser.cpp:764
sick_scan_xd::convertNAVPoseDataToTransform
ros_geometry_msgs::TransformStamped convertNAVPoseDataToTransform(NAV350PoseData &poseData, rosTime recvTimeStamp, double config_time_offset, const std::string &tf_parent_frame_id, const std::string &tf_child_frame_id, SickGenericParser *parser_)
Definition: sick_nav_scandata_parser.cpp:799
ros::Time
sick_scan_xd::readNAVIMKfile
std::vector< sick_scan_xd::NAV350ImkLandmark > readNAVIMKfile(const std::string &nav_imk_file)
Definition: sick_nav_scandata_parser.cpp:908
sick_scan_base.h
sick_scan_xd::createNAV350BinaryAddLandmarkRequest
std::vector< uint8_t > createNAV350BinaryAddLandmarkRequest(const NAV350LandmarkData &landmarkData, int nav_curr_layer)
Definition: sick_nav_scandata_parser.cpp:509
roswrap::message_traits::header
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Definition: message_traits.h:281
sick_scan_xd::parseNAV350BinaryPositionData
bool parseNAV350BinaryPositionData(const uint8_t *receiveBuffer, int receiveBufferLength, NAV350mNPOSData &navdata)
Definition: sick_nav_scandata_parser.cpp:344
sick_scan_xd::NAVOdomVelocity
::sick_scan_xd::NAVOdomVelocity_< std::allocator< void > > NAVOdomVelocity
Definition: NAVOdomVelocity.h:69
sick_scan_xd::convertNAVCartPos3DtoROSPos3D
void convertNAVCartPos3DtoROSPos3D(int32_t nav_posx_mm, int32_t nav_posy_mm, uint32_t nav_phi_mdeg, float &ros_posx_m, float &ros_posy_m, float &ros_yaw_rad, double nav_angle_offset)
Definition: sick_nav_scandata_parser.cpp:792
sick_scan_xd::convertNAVCartPos2DtoROSPos2D
void convertNAVCartPos2DtoROSPos2D(int32_t nav_posx_mm, int32_t nav_posy_mm, float &ros_posx_m, float &ros_posy_m, double nav_angle_offset)
Definition: sick_nav_scandata_parser.cpp:784
sick_scan_xd::parseNAV350BinaryLandmarkData
bool parseNAV350BinaryLandmarkData(const uint8_t *receiveBuffer, int &receivePos, int receiveBufferLength, NAV350LandmarkData &landmarkData)
Definition: sick_nav_scandata_parser.cpp:301


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