37 #include <std_msgs/Float32.h> 43 #pragma GCC diagnostic push 44 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 52 #pragma GCC diagnostic pop 105 bool should_emit =
false;
182 std::string error_string;
184 error_code =
tf_->getLatestCommonTime(
fixed_frame_, frame, latest_time, &error_string);
188 ROS_ERROR(
"Error getting latest time from frame '%s' to frame '%s': %s (Error code: %d)",
189 frame.c_str(),
fixed_frame_.c_str(), error_string.c_str(), error_code);
206 Ogre::Vector3& position,
207 Ogre::Quaternion& orientation)
216 position = Ogre::Vector3(9999999, 9999999, 9999999);
217 orientation = Ogre::Quaternion::IDENTITY;
227 position = it->second.position;
228 orientation = it->second.orientation;
232 geometry_msgs::Pose pose;
233 pose.orientation.w = 1.0f;
235 if (!
transform(frame, time, pose, position, orientation))
247 const geometry_msgs::Pose& pose_msg,
248 Ogre::Vector3& position,
249 Ogre::Quaternion& orientation)
256 position = Ogre::Vector3::ZERO;
257 orientation = Ogre::Quaternion::IDENTITY;
260 tf::Quaternion bt_orientation(pose_msg.orientation.x, pose_msg.orientation.y, pose_msg.orientation.z,
261 pose_msg.orientation.w);
262 tf::Vector3 bt_position(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z);
264 if (bt_orientation.x() == 0.0 && bt_orientation.y() == 0.0 && bt_orientation.z() == 0.0 &&
265 bt_orientation.w() == 0.0)
267 bt_orientation.setW(1.0);
278 catch (std::runtime_error& e)
280 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s': %s", frame.c_str(),
285 bt_position = pose_out.getOrigin();
286 position = Ogre::Vector3(bt_position.x(), bt_position.y(), bt_position.z());
288 bt_orientation = pose_out.getRotation();
290 Ogre::Quaternion(bt_orientation.w(), bt_orientation.x(), bt_orientation.y(), bt_orientation.z());
297 if (!
tf_->frameExists(frame))
299 error =
"Frame [" + frame +
"] does not exist";
302 error =
"Fixed " + error;
317 std::string tf_error;
318 bool transform_succeeded =
tf_->canTransform(
fixed_frame_, frame, time, &tf_error);
319 if (transform_succeeded)
330 std::stringstream ss;
331 ss <<
"No transform to fixed frame [" <<
fixed_frame_ <<
"]. TF error: [" << tf_error <<
"]";
337 std::stringstream ss;
338 ss <<
"For frame [" << frame <<
"]: " << error;
347 std::stringstream ss;
348 ss <<
"Transform [sender=" << caller_id <<
"]";
359 std::stringstream ss;
360 ss <<
"Message removed because it is too old (frame=[" << frame_id <<
"], stamp=[" << stamp <<
"])";
372 return "Unknown reason for transform failure";
382 std::stringstream ss;
383 ss <<
"Message removed because it is too old (frame=[" << frame_id <<
"], stamp=[" << stamp <<
"])";
395 return "Unknown reason for transform failure (frame=[" + frame_id +
"])";
400 const std::string& caller_id,
407 const std::string& status_text,
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_
void messageFailedImpl(const std::string &caller_id, const std::string &status_text, Display *display)
FrameManager()
Default constructor, which will create a tf::TransformListener automatically.
Helper class for transforming data into Ogre's world frame (the fixed frame).
~FrameManager() override
Destructor.
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.
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.
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.