32 #include <geometry_msgs/PoseStamped.h> 
   33 #include <geometry_msgs/Pose2D.h> 
   34 #include <nav_msgs/Odometry.h> 
   44   geometry_msgs::PoseStamped poseStampedMsg;
 
   45   if (coordinatesVersion < 
Version(
"2.0") && coordinatesVersion >= 
Version(
"1.7"))
 
   48     poseStampedMsg.pose.position.x = -body.
pose.position.x;
 
   49     poseStampedMsg.pose.position.y = body.
pose.position.z;
 
   50     poseStampedMsg.pose.position.z = body.
pose.position.y;
 
   52     poseStampedMsg.pose.orientation.x = -body.
pose.orientation.x;
 
   53     poseStampedMsg.pose.orientation.y = body.
pose.orientation.z;
 
   54     poseStampedMsg.pose.orientation.z = body.
pose.orientation.y;
 
   55     poseStampedMsg.pose.orientation.w = body.
pose.orientation.w;
 
   61     poseStampedMsg.pose.position.x = body.
pose.position.x;
 
   62     poseStampedMsg.pose.position.y = -body.
pose.position.z;
 
   63     poseStampedMsg.pose.position.z = body.
pose.position.y;
 
   65     poseStampedMsg.pose.orientation.x = body.
pose.orientation.x;
 
   66     poseStampedMsg.pose.orientation.y = -body.
pose.orientation.z;
 
   67     poseStampedMsg.pose.orientation.z = body.
pose.orientation.y;
 
   68     poseStampedMsg.pose.orientation.w = body.
pose.orientation.w;
 
   70   return poseStampedMsg;
 
   74   nav_msgs::Odometry OdometryMsg;
 
   75   if (coordinatesVersion < 
Version(
"2.0") && coordinatesVersion >= 
Version(
"1.7"))
 
   78     OdometryMsg.pose.pose.position.x = -body.
pose.position.x;
 
   79     OdometryMsg.pose.pose.position.y = body.
pose.position.z;
 
   80     OdometryMsg.pose.pose.position.z = body.
pose.position.y;
 
   82     OdometryMsg.pose.pose.orientation.x = -body.
pose.orientation.x;
 
   83     OdometryMsg.pose.pose.orientation.y = body.
pose.orientation.z;
 
   84     OdometryMsg.pose.pose.orientation.z = body.
pose.orientation.y;
 
   85     OdometryMsg.pose.pose.orientation.w = body.
pose.orientation.w;
 
   91     OdometryMsg.pose.pose.position.x = body.
pose.position.x;
 
   92     OdometryMsg.pose.pose.position.y = -body.
pose.position.z;
 
   93     OdometryMsg.pose.pose.position.z = body.
pose.position.y;
 
   95     OdometryMsg.pose.pose.orientation.x = body.
pose.orientation.x;
 
   96     OdometryMsg.pose.pose.orientation.y = -body.
pose.orientation.z;
 
   97     OdometryMsg.pose.pose.orientation.z = body.
pose.orientation.y;
 
   98     OdometryMsg.pose.pose.orientation.w = body.
pose.orientation.w;
 
  136   if (body.
pose.position.x != body.
pose.position.x)
 
  144   pose.header.stamp = time;
 
  145   odom.header.stamp = time;
 
  154                    pose.pose.orientation.y,
 
  155                    pose.pose.orientation.z,
 
  156                    pose.pose.orientation.w);
 
  173     geometry_msgs::Pose2D pose2d;
 
  174     pose2d.x = pose.pose.position.x;
 
  175     pose2d.y = pose.pose.position.y;
 
  184     transform.
setOrigin(tf::Vector3(pose.pose.position.x,
 
  185                                     pose.pose.position.y,
 
  186                                     pose.pose.position.z));
 
  203   for (
auto const& config : configs)
 
  212   std::vector<RigidBody> 
const& rigidBodies)
 
  214   for (
auto const& rigidBody : rigidBodies)
 
  220       (*iter->second).
publish(time, rigidBody);