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 
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  pose.header.frame_id = std::to_string(body.iFrame);
117  posePublisher.publish(pose);
118  }
119 
120  tf::Quaternion q(pose.pose.orientation.x,
121  pose.pose.orientation.y,
122  pose.pose.orientation.z,
123  pose.pose.orientation.w);
124 
125  if (config.publishOdom)
126  {
127  //odom.header.frame_id = config.parentFrameId;
128  odom.header.frame_id = std::to_string(body.iFrame);
129  odom.child_frame_id = config.childFrameId;
130  odomPublisher.publish(odom);
131  }
132  if (config.publishOdom)
133  {
134  odom.header.frame_id = config.parentFrameId;
135  odom.child_frame_id = config.childFrameId;
136  odomPublisher.publish(odom);
137  }
138  // publish 2D pose
139  if (config.publishPose2d)
140  {
141  geometry_msgs::Pose2D pose2d;
142  pose2d.x = pose.pose.position.x;
143  pose2d.y = pose.pose.position.y;
144  pose2d.theta = tf::getYaw(q);
145  pose2dPublisher.publish(pose2d);
146  }
147 
148  if (config.publishTf)
149  {
150  // publish transform
151  tf::Transform transform;
152  transform.setOrigin(tf::Vector3(pose.pose.position.x,
153  pose.pose.position.y,
154  pose.pose.position.z));
155 
156  transform.setRotation(q);
158  time,
159  std::to_string(body.iFrame),
161  }
162 }
163 
165  ros::NodeHandle &node,
166  Version const& sdkVersion,
167  PublisherConfigurations const& configs)
168 {
169  for (auto const& config : configs)
170  {
171  rigidBodyPublisherMap[config.rigidBodyId] =
172  RigidBodyPublisherPtr(new RigidBodyPublisher(node, sdkVersion, config));
173  }
174 }
175 
177  ros::Time const& time,
178  std::vector<RigidBody> const& rigidBodies
179  )
180 {
181  for (auto const& rigidBody : rigidBodies)
182  {
183  auto const& iter = rigidBodyPublisherMap.find(rigidBody.bodyId);
184 
185  if (iter != rigidBodyPublisherMap.end())
186  {
187  (*iter->second).publish(time, rigidBody);
188  }
189  }
190 }
191 
192 
193 } // namespace
mocap_nokov::RigidBodyPublishDispatcher::RigidBodyPublishDispatcher
RigidBodyPublishDispatcher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfigurations const &configs)
Definition: rigid_body_publisher.cpp:164
mocap_nokov::RigidBodyPublisher::tfPublisher
tf::TransformBroadcaster tfPublisher
Definition: rigid_body_publisher.h:59
mocap_nokov::RigidBody::iFrame
int iFrame
Definition: data_model.h:69
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
mocap_nokov::PublisherConfiguration
ROS publisher configuration.
Definition: mocap_config.h:56
mocap_nokov::PublisherConfiguration::pose2dTopicName
std::string pose2dTopicName
Definition: mocap_config.h:60
mocap_nokov::Version
\breif Version class containing the version information and helpers for comparison.
Definition: version.h:39
mocap_nokov::PublisherConfiguration::publishOdom
bool publishOdom
Definition: mocap_config.h:68
mocap_nokov::RigidBody::hasValidData
bool hasValidData() const
Definition: data_model.cpp:41
mocap_nokov::RigidBodyPublisher::posePublisher
ros::Publisher posePublisher
Definition: rigid_body_publisher.h:60
mocap_nokov::RigidBodyPublisher::publish
void publish(ros::Time const &time, RigidBody const &)
Definition: rigid_body_publisher.cpp:93
mocap_nokov::RigidBody::pose
Pose pose
Definition: data_model.h:71
mocap_nokov::RigidBodyPublisher::pose2dPublisher
ros::Publisher pose2dPublisher
Definition: rigid_body_publisher.h:61
mocap_nokov::PublisherConfiguration::parentFrameId
std::string parentFrameId
Definition: mocap_config.h:64
tf::StampedTransform
mocap_nokov::PublisherConfigurations
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:72
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
mocap_nokov::RigidBodyPublisher::odomPublisher
ros::Publisher odomPublisher
Definition: rigid_body_publisher.h:62
mocap_nokov::RigidBodyPublisher::config
PublisherConfiguration config
Definition: rigid_body_publisher.h:58
mocap_nokov::PublisherConfiguration::publishPose2d
bool publishPose2d
Definition: mocap_config.h:67
mocap_nokov::PublisherConfiguration::poseTopicName
std::string poseTopicName
Definition: mocap_config.h:59
tf::Transform::setRotation
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
mocap_nokov::RigidBodyPublishDispatcher::RigidBodyPublisherPtr
std::shared_ptr< RigidBodyPublisher > RigidBodyPublisherPtr
Definition: rigid_body_publisher.h:68
mocap_nokov::RigidBodyPublishDispatcher::rigidBodyPublisherMap
RigidBodyPublisherMap rigidBodyPublisherMap
Definition: rigid_body_publisher.h:70
mocap_nokov::PublisherConfiguration::publishPose
bool publishPose
Definition: mocap_config.h:66
mocap_nokov::RigidBodyPublisher
Encapsulation of a RigidBody data publisher.
Definition: rigid_body_publisher.h:48
rigid_body_publisher.h
tf::Transform
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
mocap_nokov::utilities::getRosPose
geometry_msgs::PoseStamped getRosPose(RigidBody const &body)
Definition: rigid_body_publisher.cpp:42
mocap_nokov::PublisherConfiguration::childFrameId
std::string childFrameId
Definition: mocap_config.h:63
ros::Time
mocap_nokov::PublisherConfiguration::odomTopicName
std::string odomTopicName
Definition: mocap_config.h:61
mocap_nokov::RigidBodyPublisher::RigidBodyPublisher
RigidBodyPublisher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfiguration const &config)
Definition: rigid_body_publisher.cpp:74
mocap_nokov::utilities::getRosOdom
nav_msgs::Odometry getRosOdom(RigidBody const &body)
Definition: rigid_body_publisher.cpp:57
mocap_nokov::RigidBodyPublishDispatcher::publish
void publish(ros::Time const &time, std::vector< RigidBody > const &rigidBodies)
Definition: rigid_body_publisher.cpp:176
mocap_nokov
Definition: data_model.h:39
tf::Quaternion
mocap_nokov::PublisherConfiguration::publishTf
bool publishTf
Definition: mocap_config.h:69
mocap_nokov::RigidBodyPublisher::~RigidBodyPublisher
~RigidBodyPublisher()
Definition: rigid_body_publisher.cpp:89
mocap_nokov::RigidBody
Data object holding information about a single rigid body within a mocap skeleton.
Definition: data_model.h:66
ros::NodeHandle


mocap_nokov
Author(s):
autogenerated on Mon Mar 3 2025 03:08:00