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;
116 pose.header.frame_id = std::to_string(body.
iFrame);
121 pose.pose.orientation.y,
122 pose.pose.orientation.z,
123 pose.pose.orientation.w);
128 odom.header.frame_id = std::to_string(body.
iFrame);
141 geometry_msgs::Pose2D pose2d;
142 pose2d.x = pose.pose.position.x;
143 pose2d.y = pose.pose.position.y;
152 transform.
setOrigin(tf::Vector3(pose.pose.position.x,
153 pose.pose.position.y,
154 pose.pose.position.z));
159 std::to_string(body.
iFrame),
169 for (
auto const& config : configs)
178 std::vector<RigidBody>
const& rigidBodies
181 for (
auto const& rigidBody : rigidBodies)
187 (*iter->second).
publish(time, rigidBody);