rigid_body_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, Houston Mechatronics Inc., JD Yamokoski
3  * Copyright (c) 2012, Clearpath Robotics, Inc., Alex Bencz
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * 3. Neither the name of the copyright holder nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
32 
33 #include <geometry_msgs/PoseStamped.h>
34 #include <geometry_msgs/Pose2D.h>
35 #include <nav_msgs/Odometry.h>
36 
37 namespace mocap_nokov
38 {
39 
40 namespace utilities
41 {
42  geometry_msgs::PoseStamped getRosPose(RigidBody const& body)
43  {
44  geometry_msgs::PoseStamped poseStampedMsg;
45  poseStampedMsg.pose.position.x = body.pose.position.x;
46  poseStampedMsg.pose.position.y = body.pose.position.y;
47  poseStampedMsg.pose.position.z = body.pose.position.z;
48 
49  poseStampedMsg.pose.orientation.x = body.pose.orientation.x;
50  poseStampedMsg.pose.orientation.y = body.pose.orientation.y;
51  poseStampedMsg.pose.orientation.z = body.pose.orientation.z;
52  poseStampedMsg.pose.orientation.w = body.pose.orientation.w;
53 
54  return poseStampedMsg;
55  }
56 
57  nav_msgs::Odometry getRosOdom(RigidBody const& body)
58  {
59  nav_msgs::Odometry OdometryMsg;
60 
61  OdometryMsg.pose.pose.position.x = body.pose.position.x;
62  OdometryMsg.pose.pose.position.y = body.pose.position.y;
63  OdometryMsg.pose.pose.position.z = body.pose.position.z;
64 
65  OdometryMsg.pose.pose.orientation.x = body.pose.orientation.x;
66  OdometryMsg.pose.pose.orientation.y = body.pose.orientation.y;
67  OdometryMsg.pose.pose.orientation.z = body.pose.orientation.z;
68  OdometryMsg.pose.pose.orientation.w = body.pose.orientation.w;
69 
70  return OdometryMsg;
71  }
72 }
73 
75  Version const& sdkVersion,
76  PublisherConfiguration const& config) :
77  config(config)
78 {
79  if (config.publishPose)
80  posePublisher = nh.advertise<geometry_msgs::PoseStamped>(config.poseTopicName, 1000);
81 
82  if (config.publishPose2d)
83  pose2dPublisher = nh.advertise<geometry_msgs::Pose2D>(config.pose2dTopicName, 1000);
84 
85  if (config.publishOdom)
86  odomPublisher = nh.advertise<nav_msgs::Odometry>(config.odomTopicName, 1000);
87 }
88 
90 {
91 }
92 
93 void RigidBodyPublisher::publish(ros::Time const& time, RigidBody const& body)
94 {
95  // don't do anything if no new data was provided
96  if (!body.hasValidData())
97  {
98  return;
99  }
100 
101  // NaN?
102  if (body.pose.position.x != body.pose.position.x)
103  {
104  return;
105  }
106 
107  geometry_msgs::PoseStamped pose = utilities::getRosPose(body);
108  nav_msgs::Odometry odom = utilities::getRosOdom(body);
109 
110  pose.header.stamp = time;
111  odom.header.stamp = time;
112 
113  if (config.publishPose)
114  {
115  pose.header.frame_id = config.parentFrameId;
116  posePublisher.publish(pose);
117  }
118 
119  tf::Quaternion q(pose.pose.orientation.x,
120  pose.pose.orientation.y,
121  pose.pose.orientation.z,
122  pose.pose.orientation.w);
123 
124  if (config.publishOdom)
125  {
126  odom.header.frame_id = config.parentFrameId;
127  odom.child_frame_id = config.childFrameId;
128  odomPublisher.publish(odom);
129  }
130  if (config.publishOdom)
131  {
132  odom.header.frame_id = config.parentFrameId;
133  odom.child_frame_id = config.childFrameId;
134  odomPublisher.publish(odom);
135  }
136  // publish 2D pose
137  if (config.publishPose2d)
138  {
139  geometry_msgs::Pose2D pose2d;
140  pose2d.x = pose.pose.position.x;
141  pose2d.y = pose.pose.position.y;
142  pose2d.theta = tf::getYaw(q);
143  pose2dPublisher.publish(pose2d);
144  }
145 
146  if (config.publishTf)
147  {
148  // publish transform
149  tf::Transform transform;
150  transform.setOrigin(tf::Vector3(pose.pose.position.x,
151  pose.pose.position.y,
152  pose.pose.position.z));
153 
154  transform.setRotation(q);
156  time,
159  }
160 }
161 
163  ros::NodeHandle &node,
164  Version const& sdkVersion,
165  PublisherConfigurations const& configs)
166 {
167  for (auto const& config : configs)
168  {
169  rigidBodyPublisherMap[config.rigidBodyId] =
170  RigidBodyPublisherPtr(new RigidBodyPublisher(node, sdkVersion, config));
171  }
172 }
173 
175  ros::Time const& time,
176  std::vector<RigidBody> const& rigidBodies
177  )
178 {
179  for (auto const& rigidBody : rigidBodies)
180  {
181  auto const& iter = rigidBodyPublisherMap.find(rigidBody.bodyId);
182 
183  if (iter != rigidBodyPublisherMap.end())
184  {
185  (*iter->second).publish(time, rigidBody);
186  }
187  }
188 }
189 
190 
191 } // namespace
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:72
static double getYaw(const Quaternion &bt_q)
RigidBodyPublisher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfiguration const &config)
std::shared_ptr< RigidBodyPublisher > RigidBodyPublisherPtr
Version class containing the version information and helpers for comparison.
Definition: version.h:39
tf::TransformBroadcaster tfPublisher
RigidBodyPublishDispatcher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfigurations const &configs)
void publish(const boost::shared_ptr< M > &message) const
void sendTransform(const StampedTransform &transform)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::PoseStamped getRosPose(RigidBody const &body)
Data object holding information about a single rigid body within a mocap skeleton.
Definition: data_model.h:66
nav_msgs::Odometry getRosOdom(RigidBody const &body)
bool hasValidData() const
Definition: data_model.cpp:41
void publish(ros::Time const &time, RigidBody const &)
ROS publisher configuration.
Definition: mocap_config.h:56
void publish(ros::Time const &time, std::vector< RigidBody > const &rigidBodies)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)


mocap_nokov
Author(s):
autogenerated on Sat Sep 10 2022 02:45:32