sick_tf_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2024, Ing.-Buero Dr. Michael Lehning, Hildesheim
3  * Copyright (C) 2024, SICK AG, Waldkirch
4  * All rights reserved.
5  *
6 * Licensed under the Apache License, Version 2.0 (the "License");
7 * you may not use this file except in compliance with the License.
8 * You may obtain a copy of the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS,
14 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 * See the License for the specific language governing permissions and
16 * limitations under the License.
17 *
18 *
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions are met:
23 *
24 * * Redistributions of source code must retain the above copyright
25 * notice, this list of conditions and the following disclaimer.
26 * * Redistributions in binary form must reproduce the above copyright
27 * notice, this list of conditions and the following disclaimer in the
28 * documentation and/or other materials provided with the distribution.
29 * * Neither the name of Osnabrueck University nor the names of its
30 * contributors may be used to endorse or promote products derived from
31 * this software without specific prior written permission.
32 * * Neither the name of SICK AG 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 Ing.-Buero Dr. Michael Lehning 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 *
39 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
40 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
41 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
42 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
43 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
44 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
45 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
46 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
47 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
48 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
49 * POSSIBILITY OF SUCH DAMAGE.
50  *
51  * Created on: 15th March 2024
52  *
53  * Authors:
54  * Michael Lehning <michael.lehning@lehning.de>
55  *
56  */
57 
62 
63 namespace sick_scan_xd
64 {
65  /*
66  ** @brief On ROS-1 and ROS-2, SickTransformPublisher publishes TF messsages to map a given base frame
67  ** (i.e. base coordinates system) to the lidar frame (i.e. lidar coordinates system) and vice versa.
68  **
69  ** The default base frame id is "map" (which is the default frame in rviz).
70  ** The default 6D pose is (x,y,z,roll,pitch,yaw) = (0,0,0,0,0,0) defined by
71  ** position (x,y,z) in meter and (roll,pitch,yaw) in radians.
72  ** This 6D pose (x,y,z,roll,pitch,yaw) is the transform T[base,lidar] with
73  ** parent "base" and child "lidar".
74  **
75  ** For lidars mounted on a carrier, the lidar pose T[base,lidar] can be configured in the launchfile:
76  ** <param name="tf_base_frame_id" type="string" value="map" /> <!-- Frame id of base coordinates system, e.g. "map" (default frame in rviz) -->
77  ** <param name="tf_base_lidar_xyz_rpy" type="string" value="0,0,0,0,0,0" /> <!-- T[base,lidar], 6D pose (x,y,z,roll,pitch,yaw) in meter resp. radians with parent "map" and child "cloud" -->
78  ** <param name="tf_publish_rate" type="double" value="10" /> <!-- Rate to publish TF messages in hz, use 0 to deactivate TF messages -->
79  **
80  ** The lidar frame id given by parameter "frame_id" resp. "publish_frame_id".
81  **
82  ** Note that SickTransformPublisher configures the transform using (x,y,z,roll,pitch,yaw).
83  ** In contrast, the ROS static_transform_publisher uses commandline arguments in order (x,y,z,yaw,pitch,roll).
84  **
85  */
86 
88  {
89 # if __ROS_VERSION > 0
90  if (_nh)
91  {
92  // SickTransformPublisher configuration
93  nh = _nh;
94  std::string scanner_type;
95  rosDeclareParam(nh, "scanner_type", scanner_type);
96  rosGetParam(nh, "scanner_type", scanner_type);
97  if (scanner_type == SICK_SCANNER_SCANSEGMENT_XD_NAME || scanner_type == SICK_SCANNER_PICOSCAN_NAME)
98  {
99  rosDeclareParam(nh, "publish_frame_id", tf_lidar_frame_id);
100  rosGetParam(nh, "publish_frame_id", tf_lidar_frame_id);
101  }
102  else
103  {
104  rosDeclareParam(nh, "frame_id", tf_lidar_frame_id);
105  rosGetParam(nh, "frame_id", tf_lidar_frame_id);
106  }
107  rosDeclareParam(nh, "tf_base_frame_id", tf_base_frame_id);
108  rosGetParam(nh, "tf_base_frame_id", tf_base_frame_id);
109  rosDeclareParam(nh, "tf_base_lidar_xyz_rpy", tf_base_lidar_xyz_rpy);
110  rosGetParam(nh, "tf_base_lidar_xyz_rpy", tf_base_lidar_xyz_rpy);
111  rosDeclareParam(nh, "tf_publish_rate", tf_publish_rate);
112  rosGetParam(nh, "tf_publish_rate", tf_publish_rate);
113  // Split string tf_base_lidar_xyz_rpy to 6D pose x,y,z,roll,pitch,yaw in [m] resp. [rad]
114  tf_base_lidar_pose_vec = sick_scan_xd::parsePose(tf_base_lidar_xyz_rpy);
115  if(tf_base_lidar_pose_vec.size() != 6)
116  {
117  ROS_ERROR_STREAM("## ERROR SickTransformPublisher(): Can't parse config string \"" << tf_base_lidar_xyz_rpy << "\", use 6D pose \"x,y,z,roll,pitch,yaw\" in [m] resp. [rad], using TF messages with default pose (0,0,0,0,0,0)");
118  tf_base_lidar_pose_vec = std::vector<float>(6, 0);
119  }
120  ROS_INFO_STREAM("SickTransformPublisher: broadcasting TF messages parent_frame_id=\"" << tf_base_frame_id << "\", child_frame_id=\"" << tf_lidar_frame_id
121  << "\", (x,y,z,roll,pitch,yaw)=(" << std::fixed << std::setprecision(1) << tf_base_lidar_pose_vec[0] << "," << tf_base_lidar_pose_vec[1] << "," << tf_base_lidar_pose_vec[2]
122  << "," << (tf_base_lidar_pose_vec[3]*180.0/M_PI) << "," << (tf_base_lidar_pose_vec[4]*180.0/M_PI) << "," << (tf_base_lidar_pose_vec[5]*180.0/M_PI)
123  << "), rate=" << tf_publish_rate);
124  }
125 # endif
126  }
127 
129  {
130 # if __ROS_VERSION > 0
131  if(tf_publish_rate > 1.0e-6)
132  {
133  tf_publish_thread_running = true;
134  tf_publish_thread = new std::thread(&sick_scan_xd::SickTransformPublisher::runTFpublishThreadCb, this);
135  }
136 # endif
137  }
138 
140  {
141 # if __ROS_VERSION > 0
142  tf_publish_thread_running = false;
143  if (tf_publish_thread && tf_publish_thread->joinable())
144  tf_publish_thread->join();
145  if (tf_publish_thread)
146  delete tf_publish_thread;
147  tf_publish_thread = 0;
148 # endif
149  }
150 
151 # if __ROS_VERSION > 0
152  void SickTransformPublisher::runTFpublishThreadCb()
153  {
154  assert(tf_publish_rate > 0);
155  assert(tf_base_lidar_pose_vec.size() == 6); // 6D pose x,y,z,roll,pitch,yaw in [m] resp. [rad]
156  int publish_sleep_millisec = int(1000.0 / tf_publish_rate);
158  tf_message.header.frame_id = tf_base_frame_id;
159  tf_message.child_frame_id = tf_lidar_frame_id;
160  tf_message.transform.translation.x = tf_base_lidar_pose_vec[0];
161  tf_message.transform.translation.y = tf_base_lidar_pose_vec[1];
162  tf_message.transform.translation.z = tf_base_lidar_pose_vec[2];
163  tf2::Quaternion q;
164  q.setRPY(tf_base_lidar_pose_vec[3], tf_base_lidar_pose_vec[4], tf_base_lidar_pose_vec[5]);
165  tf_message.transform.rotation.x = q.x();
166  tf_message.transform.rotation.y = q.y();
167  tf_message.transform.rotation.z = q.z();
168  tf_message.transform.rotation.w = q.w();
169 # if __ROS_VERSION == 1
170  tf2_ros::TransformBroadcaster tf_broadcaster;
171 # elif __ROS_VERSION == 2
172  tf2_ros::TransformBroadcaster tf_broadcaster(nh);
173 # endif
174  while (rosOk() && tf_publish_thread_running)
175  {
176  tf_message.header.stamp = rosTimeNow();
177  tf_broadcaster.sendTransform(tf_message);
178  std::this_thread::sleep_for(std::chrono::milliseconds(publish_sleep_millisec));
179  }
180  tf_publish_thread_running = false;
181  }
182 # endif
183 
184 
185 } // namespace sick_scan_xd
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
geometry_msgs::TransformStamped
::geometry_msgs::TransformStamped_< std::allocator< void > > TransformStamped
Definition: TransformStamped.h:60
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_common.h
sick_scan_xd::SickTransformPublisher::SickTransformPublisher
SickTransformPublisher(rosNodePtr _nh=0)
Definition: sick_tf_publisher.cpp:87
ROS_INFO_STREAM
#define ROS_INFO_STREAM(...)
Definition: sick_scan_ros2_example.cpp:71
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
sick_generic_parser.h
sick_tf_publisher.h
sick_scan_parse_util.h
sick_scan_xd::parsePose
std::vector< float > parsePose(const std::string &pose_xyz_rpy_str)
Definition: sick_scan_parse_util.cpp:100
ros::NodeHandle
rosGetParam
bool rosGetParam(rosNodePtr nh, const std::string &param_name, T &param_value)
Definition: sick_ros_wrapper.h:167
sick_scan_xd::SickTransformPublisher::stop
void stop()
Definition: sick_tf_publisher.cpp:139
rosTimeNow
rosTime rosTimeNow(void)
Definition: sick_ros_wrapper.h:173
sick_scan_xd::SickTransformPublisher::run
void run()
Definition: sick_tf_publisher.cpp:128
tf2_ros::TransformBroadcaster
This class provides an easy way to publish coordinate frame transform information....
Definition: transform_broadcaster.h:49
tf2::Quaternion
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: melodic/include/tf2/LinearMath/Quaternion.h:29
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(...)
Definition: sick_scan_ros2_example.cpp:72
rosOk
bool rosOk(void)
Definition: sick_ros_wrapper.h:206
SICK_SCANNER_SCANSEGMENT_XD_NAME
#define SICK_SCANNER_SCANSEGMENT_XD_NAME
Definition: sick_generic_parser.h:82
rosDeclareParam
void rosDeclareParam(rosNodePtr nh, const std::string &param_name, const T &param_value)
Definition: sick_ros_wrapper.h:166
SICK_SCANNER_PICOSCAN_NAME
#define SICK_SCANNER_PICOSCAN_NAME
Definition: sick_generic_parser.h:83


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