37 #include <std_msgs/Float32.h>   167         std::string error_string;
   169         error_code = 
tf_->getLatestCommonTime( 
fixed_frame_, frame, latest_time, &error_string );
   171         if ( error_code != 0 )
   173           ROS_ERROR(
"Error getting latest time from frame '%s' to frame '%s': %s (Error code: %d)", frame.c_str(), 
fixed_frame_.c_str(), error_string.c_str(), error_code);
   198   position = Ogre::Vector3(9999999, 9999999, 9999999);
   199   orientation = Ogre::Quaternion::IDENTITY;
   209     position = it->second.position;
   210     orientation = it->second.orientation;
   214   geometry_msgs::Pose pose;
   215   pose.orientation.w = 1.0f;
   217   if (!
transform(frame, time, pose, position, orientation))
   234   position = Ogre::Vector3::ZERO;
   235   orientation = Ogre::Quaternion::IDENTITY;
   238   tf::Quaternion bt_orientation(pose_msg.orientation.x, pose_msg.orientation.y, pose_msg.orientation.z, pose_msg.orientation.w);
   239   tf::Vector3 bt_position(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z);
   241   if (bt_orientation.x() == 0.0 && bt_orientation.y() == 0.0 && bt_orientation.z() == 0.0 && bt_orientation.w() == 0.0)
   243     bt_orientation.setW(1.0);
   254   catch(std::runtime_error& e)
   256     ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s': %s", frame.c_str(), 
fixed_frame_.c_str(), e.what());
   260   bt_position = pose_out.getOrigin();
   261   position = Ogre::Vector3(bt_position.
x(), bt_position.
y(), bt_position.
z());
   263   bt_orientation = pose_out.getRotation();
   264   orientation = Ogre::Quaternion( bt_orientation.w(), bt_orientation.x(), bt_orientation.y(), bt_orientation.z() );
   271   if (!
tf_->frameExists(frame))
   273     error = 
"Frame [" + frame + 
"] does not exist";
   276       error = 
"Fixed " + error;
   291   std::string tf_error;
   292   bool transform_succeeded = 
tf_->canTransform(
fixed_frame_, frame, time, &tf_error);
   293   if (transform_succeeded)
   304     std::stringstream ss;
   305     ss << 
"No transform to fixed frame [" << 
fixed_frame_ << 
"].  TF error: [" << tf_error << 
"]";
   311     std::stringstream ss;
   312     ss << 
"For frame [" << frame << 
"]: " << error;
   321   std::stringstream ss;
   322   ss << 
"Transform [sender=" << caller_id << 
"]";
   330     std::stringstream ss;
   331     ss << 
"Message removed because it is too old (frame=[" << frame_id << 
"], stamp=[" << stamp << 
"])";
   343   return "Unknown reason for transform failure";
   347                                    const std::string& caller_id, 
Display* display )
 bool adjustTime(const std::string &frame, ros::Time &time)
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
std::string discoverFailureReason(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason)
Create a description of a transform problem. 
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a transform is known between a given frame and the fixed frame. 
std::string getTransformStatusName(const std::string &caller_id)
boost::mutex cache_mutex_
void update()
Clear the internal cache. 
void messageArrived(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, Display *display)
boost::shared_ptr< tf::TransformListener > tf_
TFSIMD_FORCE_INLINE const tfScalar & x() const 
TFSIMD_FORCE_INLINE const tfScalar & z() const 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame. 
void setPause(bool pause)
Enable/disable pause mode. 
FrameManager(boost::shared_ptr< tf::TransformListener > tf=boost::shared_ptr< tf::TransformListener >())
Constructor. 
void syncTime(ros::Time time)
Synchronize with given time. 
void setFixedFrame(const std::string &frame)
Set the frame to consider "fixed", into which incoming data is transformed. 
void messageFailed(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason, Display *display)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes. 
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a frame exists in the tf::TransformListener. 
void setSyncMode(SyncMode mode)
Set synchronization mode (off/exact/approximate) 
void fixedFrameChanged()
Emitted whenever the fixed frame changes. 
~FrameManager()
Destructor.