33 #include <geometry_msgs/PoseStamped.h> 34 #include <geometry_msgs/Pose2D.h> 35 #include <nav_msgs/Odometry.h> 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;
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;
54 return poseStampedMsg;
59 nav_msgs::Odometry OdometryMsg;
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;
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;
102 if (body.
pose.position.x != body.
pose.position.x)
110 pose.header.stamp = time;
111 odom.header.stamp = time;
120 pose.pose.orientation.y,
121 pose.pose.orientation.z,
122 pose.pose.orientation.w);
139 geometry_msgs::Pose2D pose2d;
140 pose2d.x = pose.pose.position.x;
141 pose2d.y = pose.pose.position.y;
150 transform.
setOrigin(tf::Vector3(pose.pose.position.x,
151 pose.pose.position.y,
152 pose.pose.position.z));
167 for (
auto const&
config : configs)
176 std::vector<RigidBody>
const& rigidBodies
179 for (
auto const& rigidBody : rigidBodies)
181 auto const& iter = rigidBodyPublisherMap.find(rigidBody.bodyId);
183 if (iter != rigidBodyPublisherMap.end())
185 (*iter->second).
publish(time, rigidBody);
std::vector< PublisherConfiguration > PublisherConfigurations
ros::Publisher odomPublisher
static double getYaw(const Quaternion &bt_q)
RigidBodyPublisher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfiguration const &config)
std::string odomTopicName
std::shared_ptr< RigidBodyPublisher > RigidBodyPublisherPtr
Version class containing the version information and helpers for comparison.
tf::TransformBroadcaster tfPublisher
std::string parentFrameId
ros::Publisher posePublisher
RigidBodyPublishDispatcher(ros::NodeHandle &node, Version const &sdkVersion, PublisherConfigurations const &configs)
void publish(const boost::shared_ptr< M > &message) const
PublisherConfiguration config
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::PoseStamped getRosPose(RigidBody const &body)
std::string poseTopicName
Data object holding information about a single rigid body within a mocap skeleton.
nav_msgs::Odometry getRosOdom(RigidBody const &body)
bool hasValidData() const
void publish(ros::Time const &time, RigidBody const &)
std::string pose2dTopicName
ROS publisher configuration.
void publish(ros::Time const &time, std::vector< RigidBody > const &rigidBodies)
ros::Publisher pose2dPublisher