00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "frame_manager.h"
00031 #include "common.h"
00032 #include "display.h"
00033 #include "properties/property.h"
00034
00035 #include <tf/transform_listener.h>
00036 #include <ros/ros.h>
00037
00038 namespace rviz
00039 {
00040
00041 FrameManagerPtr FrameManager::instance()
00042 {
00043 static FrameManagerWPtr instw;
00044
00045 FrameManagerPtr inst = instw.lock();
00046 if (!inst)
00047 {
00048 inst.reset(new FrameManager);
00049 instw = inst;
00050 }
00051
00052 return inst;
00053 }
00054
00055 FrameManager::FrameManager()
00056 {
00057 tf_ = new tf::TransformListener(ros::NodeHandle(), ros::Duration(10*60), false);
00058 }
00059
00060 FrameManager::~FrameManager()
00061 {
00062 delete tf_;
00063 }
00064
00065 void FrameManager::update()
00066 {
00067 boost::mutex::scoped_lock lock(cache_mutex_);
00068 cache_.clear();
00069 }
00070
00071 void FrameManager::setFixedFrame(const std::string& frame)
00072 {
00073 boost::mutex::scoped_lock lock(cache_mutex_);
00074 fixed_frame_ = frame;
00075 cache_.clear();
00076 }
00077
00078 bool FrameManager::getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation)
00079 {
00080 boost::mutex::scoped_lock lock(cache_mutex_);
00081
00082 position = Ogre::Vector3(9999999, 9999999, 9999999);
00083 orientation = Ogre::Quaternion::IDENTITY;
00084
00085 if (fixed_frame_.empty())
00086 {
00087 return false;
00088 }
00089
00090 M_Cache::iterator it = cache_.find(CacheKey(frame, time, relative_orientation));
00091 if (it != cache_.end())
00092 {
00093 position = it->second.position;
00094 orientation = it->second.orientation;
00095 return true;
00096 }
00097
00098 geometry_msgs::Pose pose;
00099 pose.orientation.w = 1.0f;
00100
00101 if (!transform(frame, time, pose, position, orientation, relative_orientation))
00102 {
00103 return false;
00104 }
00105
00106 cache_.insert(std::make_pair(CacheKey(frame, time, relative_orientation), CacheEntry(position, orientation)));
00107
00108 return true;
00109 }
00110
00111 bool FrameManager::transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose_msg, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation)
00112 {
00113 position = Ogre::Vector3::ZERO;
00114 orientation = Ogre::Quaternion::IDENTITY;
00115
00116 btQuaternion btorient(pose_msg.orientation.x, pose_msg.orientation.y, pose_msg.orientation.z, pose_msg.orientation.w);
00117 if (btorient.x() == 0.0 && btorient.y() == 0.0 && btorient.z() == 0.0 && btorient.w() == 0.0)
00118 {
00119 btorient.setW(1.0);
00120 }
00121
00122 tf::Stamped<tf::Pose> pose(btTransform(btorient,
00123 btVector3(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z)),
00124 time, frame);
00125 try
00126 {
00127 tf_->transformPose( fixed_frame_, pose, pose );
00128 }
00129 catch(tf::TransformException& e)
00130 {
00131 ROS_DEBUG("Error transforming from frame '%s' to frame '%s': %s", frame.c_str(), fixed_frame_.c_str(), e.what());
00132 return false;
00133 }
00134
00135 position = Ogre::Vector3(pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z());
00136 robotToOgre(position);
00137
00138 btQuaternion quat;
00139 pose.getBasis().getRotation( quat );
00140 orientation = Ogre::Quaternion::IDENTITY;
00141
00142 if (relative_orientation)
00143 {
00144 ogreToRobot(orientation);
00145 }
00146
00147 orientation = Ogre::Quaternion( quat.w(), quat.x(), quat.y(), quat.z() ) * orientation;
00148 robotToOgre(orientation);
00149
00150 return true;
00151 }
00152
00153 bool FrameManager::frameHasProblems(const std::string& frame, ros::Time time, std::string& error)
00154 {
00155 if (!tf_->frameExists(frame))
00156 {
00157 error = "Frame [" + frame + "] does not exist";
00158 if (frame == fixed_frame_)
00159 {
00160 error = "Fixed " + error;
00161 }
00162 return true;
00163 }
00164
00165 return false;
00166 }
00167
00168 bool FrameManager::transformHasProblems(const std::string& frame, ros::Time time, std::string& error)
00169 {
00170 std::string tf_error;
00171 bool transform_succeeded = tf_->canTransform(fixed_frame_, frame, time, &tf_error);
00172 if (transform_succeeded)
00173 {
00174 return false;
00175 }
00176
00177 bool ok = true;
00178 ok = ok && !frameHasProblems(fixed_frame_, time, error);
00179 ok = ok && !frameHasProblems(frame, time, error);
00180
00181 if (ok)
00182 {
00183 std::stringstream ss;
00184 ss << "No transform to fixed frame [" << fixed_frame_ << "]. TF error: [" << tf_error << "]";
00185 error = ss.str();
00186 ok = false;
00187 }
00188
00189 {
00190 std::stringstream ss;
00191 ss << "For frame [" << frame << "]: " << error;
00192 error = ss.str();
00193 }
00194
00195 return !ok;
00196 }
00197
00198 std::string getTransformStatusName(const std::string& caller_id)
00199 {
00200 std::stringstream ss;
00201 ss << "Transform [sender=" << caller_id << "]";
00202 return ss.str();
00203 }
00204
00205 std::string FrameManager::discoverFailureReason(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason)
00206 {
00207 if (reason == tf::filter_failure_reasons::OutTheBack)
00208 {
00209 std::stringstream ss;
00210 ss << "Message removed because it is too old (frame=[" << frame_id << "], stamp=[" << stamp << "])";
00211 return ss.str();
00212 }
00213 else
00214 {
00215 std::string error;
00216 if (transformHasProblems(frame_id, stamp, error))
00217 {
00218 return error;
00219 }
00220 }
00221
00222 return "Unknown reason for transform failure";
00223 }
00224
00225 void FrameManager::messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display)
00226 {
00227 display->setStatus(status_levels::Ok, getTransformStatusName(caller_id), "Transform OK");
00228 }
00229
00230 void FrameManager::messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason, Display* display)
00231 {
00232 std::string status_name = getTransformStatusName(caller_id);
00233 std::string status_text = discoverFailureReason(frame_id, stamp, caller_id, reason);
00234 display->setStatus(status_levels::Error, status_name, status_text);
00235 }
00236
00237 }