TransformPublisherDisplay.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, Bielefeld University, CITEC
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Robert Haschke <rhaschke@techfak.uni-bielefeld.de>
30  */
31 
33 #include "TransformBroadcaster.h"
34 #include "rotation_property.h"
35 
42 
43 #include <rviz/display_factory.h>
44 #include <rviz/display_context.h>
45 #include <rviz/frame_manager.h>
49 
50 namespace vm = visualization_msgs;
51 const std::string MARKER_NAME = "marker";
52 
54 
55 namespace agni_tf_tools {
56 
57 void static updatePose(geometry_msgs::Pose& pose,
58  const Eigen::Quaterniond& q,
59  Ogre::Vector3 p = Ogre::Vector3::ZERO) {
60  pose.orientation.w = q.w();
61  pose.orientation.x = q.x();
62  pose.orientation.y = q.y();
63  pose.orientation.z = q.z();
64 
65  pose.position.x = p.x;
66  pose.position.y = p.y;
67  pose.position.z = p.z;
68 }
69 
70 
72  : rviz::Display(), tf_callback_handle_(0), tf_request_handle_(0), ignore_updates_(false) {
73  translation_property_ = new rviz::VectorProperty("translation", Ogre::Vector3::ZERO, "", this);
74  rotation_property_ = new RotationProperty(this, "rotation");
75 
78  nullptr, true, SLOT(onRefFrameChanged()), this);
80  new rviz::BoolProperty("adapt transformation", false,
81  "Adapt transformation when changing the parent frame? "
82  "If so, the marker will not move.",
83  this, SLOT(onAdaptTransformChanged()), this);
85 
86  broadcast_property_ = new rviz::BoolProperty("publish transform", true, "", this,
87  SLOT(onBroadcastEnableChanged()), this);
88  child_frame_property_ = new rviz::TfFrameProperty("child frame", "", "", broadcast_property_, nullptr,
89  false, SLOT(onFramesChanged()), this);
90 
97  tf_pub_ = new TransformBroadcaster("", "", this);
98  tf_pub_->setEnabled(false); // only enable with display
99 
100  marker_property_ = new rviz::EnumProperty("marker type", "interactive frame",
101  "Choose which type of interactive marker to show", this,
102  SLOT(onMarkerTypeChanged()), this);
103  marker_property_->addOption("none", NONE);
104  marker_property_->addOption("static frame", FRAME);
105  marker_property_->addOption("interactive frame", IFRAME);
106  marker_property_->addOption("6 DoF handles", DOF6);
107 
108  marker_scale_property_ = new rviz::FloatProperty("marker scale", 0.2, "", marker_property_,
109  SLOT(onMarkerScaleChanged()), this);
110 }
111 
113  context_->getTF2BufferPtr()->removeTransformableCallback(tf_callback_handle_);
114 }
115 
117  Display::onInitialize();
120  tf_callback_handle_ = context_->getTF2BufferPtr()->addTransformableCallback(
121  boost::bind(&TransformPublisherDisplay::onFramesChanged, this));
122 
123  // show some children by default
124  this->expand();
126 }
127 
129  Display::reset();
130 }
131 
133  Display::onEnable();
134  onFramesChanged();
136 }
137 
139  Display::onDisable();
142 }
143 
144 void TransformPublisherDisplay::update(float wall_dt, float ros_dt) {
145  if (!this->isEnabled())
146  return;
147 
148  Display::update(wall_dt, ros_dt);
149  // create marker if not yet done
150  if (!imarker_ && marker_property_->getOptionInt() != NONE &&
153  else if (imarker_)
154  imarker_->update(wall_dt); // get online marker updates
155 }
156 
157 
158 static vm::Marker createArrowMarker(double scale, const Eigen::Vector3d& dir, const QColor& color) {
159  vm::Marker marker;
160 
161  marker.type = vm::Marker::ARROW;
162  marker.scale.x = scale;
163  marker.scale.y = 0.1 * scale;
164  marker.scale.z = 0.1 * scale;
165 
166  updatePose(marker.pose, Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitX(), dir));
167 
168  marker.color.r = color.redF();
169  marker.color.g = color.greenF();
170  marker.color.b = color.blueF();
171  marker.color.a = color.alphaF();
172 
173  return marker;
174 }
175 
176 inline void setOrientation(geometry_msgs::Quaternion& q, double w, double x, double y, double z) {
177  q.w = w;
178  q.x = x;
179  q.y = y;
180  q.z = z;
181 }
182 
183 void TransformPublisherDisplay::addFrameControls(vm::InteractiveMarker& im,
184  double scale,
185  bool interactive) {
186  vm::InteractiveMarkerControl ctrl;
187  setOrientation(ctrl.orientation, 1, 0, 0, 0);
188  ctrl.always_visible = true;
189  if (interactive) {
190  ctrl.orientation_mode = vm::InteractiveMarkerControl::VIEW_FACING;
191  ctrl.independent_marker_orientation = true;
192  ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_ROTATE_3D;
193  }
194  ctrl.name = "frame";
195 
196  ctrl.markers.push_back(createArrowMarker(im.scale * scale, Eigen::Vector3d::UnitX(), QColor("red")));
197  ctrl.markers.push_back(createArrowMarker(im.scale * scale, Eigen::Vector3d::UnitY(), QColor("green")));
198  ctrl.markers.push_back(createArrowMarker(im.scale * scale, Eigen::Vector3d::UnitZ(), QColor("blue")));
199 
200  im.controls.push_back(ctrl);
201 }
202 
203 void TransformPublisherDisplay::add6DOFControls(vm::InteractiveMarker& im) {
204  vm::InteractiveMarkerControl ctrl;
205  ctrl.always_visible = false;
206 
207  setOrientation(ctrl.orientation, 1, 1, 0, 0);
208  ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
209  ctrl.name = "x pos";
210  im.controls.push_back(ctrl);
211  ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
212  ctrl.name = "x rot";
213  im.controls.push_back(ctrl);
214 
215  setOrientation(ctrl.orientation, 1, 0, 1, 0);
216  ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
217  ctrl.name = "y pos";
218  im.controls.push_back(ctrl);
219  ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
220  ctrl.name = "y rot";
221  im.controls.push_back(ctrl);
222 
223  setOrientation(ctrl.orientation, 1, 0, 0, 1);
224  ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
225  ctrl.name = "z pos";
226  im.controls.push_back(ctrl);
227  ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
228  ctrl.name = "z rot";
229  im.controls.push_back(ctrl);
230 }
231 
233  if (type == NONE || !isEnabled()) {
234  if (imarker_)
235  imarker_.reset();
236  return true;
237  }
238 
239  float scale = marker_scale_property_->getFloat();
240 
241  vm::InteractiveMarker im;
242  im.name = MARKER_NAME;
243  im.scale = scale;
244  if (!fillPoseStamped(im.header, im.pose))
245  return false;
246 
247  if (type == FRAME || type == IFRAME)
248  addFrameControls(im, 1.0, type == IFRAME);
249  else if (type == DOF6) {
250  addFrameControls(im, 0.5, type == IFRAME);
251  add6DOFControls(im);
252  }
253 
255  connect(imarker_.get(), &rviz::InteractiveMarker::userFeedback, this,
257  connect(imarker_.get(), &rviz::InteractiveMarker::statusUpdate, this,
259 
261 
262  // fill in default controls
264 
265  imarker_->processMessage(im);
266  imarker_->setShowVisualAids(false);
267  imarker_->setShowAxes(false);
268  imarker_->setShowDescription(false);
269 
270  return true;
271 }
272 
274  if (tf_request_handle_) {
275  context_->getTF2BufferPtr()->cancelTransformableRequest(tf_request_handle_);
276  tf_request_handle_ = 0;
277  }
278 }
279 
280 bool TransformPublisherDisplay::fillPoseStamped(std_msgs::Header& header, geometry_msgs::Pose& pose) {
281  const std::string& parent_frame = parent_frame_property_->getFrameStd();
282  std::string error;
283  bool success = true;
284  if (context_->getFrameManager()->transformHasProblems(parent_frame, ros::Time(), error)) {
285  if (!tf_request_handle_) // on failure, listen to TF changes
286  tf_request_handle_ = context_->getTF2BufferPtr()->addTransformableRequest(
287  tf_callback_handle_, fixed_frame_.toStdString(), parent_frame, ros::Time());
289  success = false;
290  } else {
291  if (tf_request_handle_)
292  cancelTFRequest();
294  }
295 
296  const Eigen::Quaterniond& q = rotation_property_->getQuaternion();
297  const Ogre::Vector3& p = translation_property_->getVector();
298  updatePose(pose, q, p);
299  header.frame_id = parent_frame;
300  // frame-lock marker to update marker pose with frame updates
301  header.stamp = ros::Time();
302  return success;
303 }
304 
305 static bool getTransform(rviz::FrameManager& fm, const std::string& frame, Eigen::Affine3d& tf) {
306  Ogre::Vector3 p = Ogre::Vector3::ZERO;
307  Ogre::Quaternion q = Ogre::Quaternion::IDENTITY;
308 
309  bool success = fm.getTransform(frame, ros::Time(), p, q);
310  tf = Eigen::Translation3d(p.x, p.y, p.z) * Eigen::Quaterniond(q.w, q.x, q.y, q.z);
311  return success || frame == rviz::TfFrameProperty::FIXED_FRAME_STRING.toStdString();
312 }
313 
315  // update pose to be relative to new reference frame
316  Eigen::Affine3d prevRef, nextRef;
318  if (getTransform(fm, prev_parent_frame_, prevRef) &&
320  const Ogre::Vector3& p = translation_property_->getVector();
321  Eigen::Affine3d curPose = Eigen::Translation3d(p.x, p.y, p.z) * rotation_property_->getQuaternion();
322  Eigen::Affine3d newPose = nextRef.inverse() * prevRef * curPose;
323  Eigen::Vector3d t = newPose.translation();
324  ignore_updates_ = true;
325  translation_property_->setVector(Ogre::Vector3(t.x(), t.y(), t.z()));
326  rotation_property_->setQuaternion(Eigen::Quaterniond(newPose.rotation()));
327  ignore_updates_ = false;
328  }
329  cancelTFRequest(); // create a new TF request (for the new parent frame) if necessary
331  onFramesChanged();
332 }
333 
337  else
338  prev_parent_frame_ = "";
339 }
340 
342  // update marker pose
343  vm::InteractiveMarkerPose marker_pose;
344  if (fillPoseStamped(marker_pose.header, marker_pose.pose) && imarker_)
345  imarker_->processMessage(marker_pose);
346 
347  // prepare transform for broadcasting
348  geometry_msgs::TransformStamped tf;
349  tf.header.frame_id = parent_frame_property_->getFrameStd();
350  tf.child_frame_id = child_frame_property_->getFrameStd();
351  tf.transform.translation.x = marker_pose.pose.position.x;
352  tf.transform.translation.y = marker_pose.pose.position.y;
353  tf.transform.translation.z = marker_pose.pose.position.z;
354  tf.transform.rotation = marker_pose.pose.orientation;
355  tf_pub_->setValue(tf);
356 }
357 
359  if (ignore_updates_)
360  return;
361 
362  // update marker pose + broadcast pose
363  ignore_updates_ = true;
364  vm::InteractiveMarkerPose marker_pose;
365  if (fillPoseStamped(marker_pose.header, marker_pose.pose) && imarker_)
366  imarker_->processMessage(marker_pose);
367  ignore_updates_ = false;
368 
369  tf_pub_->setPose(marker_pose.pose);
370 }
371 
372 void TransformPublisherDisplay::onMarkerFeedback(vm::InteractiveMarkerFeedback& feedback) {
373  if (ignore_updates_)
374  return;
375  if (feedback.event_type != vm::InteractiveMarkerFeedback::POSE_UPDATE)
376  return;
377 
378  // convert feedpack.pose to parent frame
379  geometry_msgs::Pose pose;
380  try {
381  tf2::doTransform(feedback.pose, pose,
383  feedback.header.frame_id,
384  feedback.header.stamp));
385  } catch (const std::runtime_error& e) {
386  ROS_DEBUG("Error transforming from frame '%s' to frame '%s': %s", feedback.header.frame_id.c_str(),
387  parent_frame_property_->getFrameStd().c_str(), e.what());
388  return;
389  }
390 
391  const geometry_msgs::Point& p = pose.position;
392  const geometry_msgs::Quaternion& q = pose.orientation;
393 
394  ignore_updates_ = true;
395  translation_property_->setVector(Ogre::Vector3(p.x, p.y, p.z));
396  rotation_property_->setQuaternion(Eigen::Quaterniond(q.w, q.x, q.y, q.z));
397  ignore_updates_ = false;
398 
400  tf_pub_->setPose(feedback.pose);
401 }
402 
405 }
406 
409 }
410 
412  if (marker_scale_property_->getFloat() <= 0)
415 }
416 
417 } // namespace agni_tf_tools
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
const std::string MARKER_NAME
std::string getFrameStd() const
virtual void expand()
virtual bool setVector(const Ogre::Vector3 &vector)
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
DisplayContext * context_
tf2::TransformableCallbackHandle tf_callback_handle_
virtual Ogre::Vector3 getVector() const
void quaternionChanged(Eigen::Quaterniond q)
void add6DOFControls(visualization_msgs::InteractiveMarker &im)
INTERACTIVE_MARKERS_PUBLIC void autoComplete(visualization_msgs::InteractiveMarker &msg, bool enable_autocomplete_transparency=true)
static vm::Marker createArrowMarker(double scale, const Eigen::Vector3d &dir, const QColor &color)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
geometry_msgs::TransformStamped t
void setOrientation(geometry_msgs::Quaternion &q, double w, double x, double y, double z)
void onMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
QString fixed_frame_
bool setFloat(float new_value)
tf2::TransformableRequestHandle tf_request_handle_
virtual void addOption(const QString &option, int value=0)
Ogre::SceneNode * getSceneNode() const
void update(float wall_dt, float ros_dt) override
boost::shared_ptr< rviz::InteractiveMarker > imarker_
void setQuaternion(const Eigen::Quaterniond &q)
virtual FrameManager * getFrameManager() const=0
void statusUpdate(rviz::StatusProperty::Level, const QString &, const QString &)
void addFrameControls(visualization_msgs::InteractiveMarker &im, double scale, bool interactive)
Eigen::Quaterniond getQuaternion() const
void userFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
void setEnabled(bool bEnabled=true)
virtual std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const=0
bool isEnabled() const
static const QString FIXED_FRAME_STRING
virtual float getFloat() const
static bool getTransform(rviz::FrameManager &fm, const std::string &frame, Eigen::Affine3d &tf)
void statusUpdate(StatusProperty::Level level, const std::string &name, const std::string &text)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
void setPose(const geometry_msgs::Pose &pose)
static void updatePose(geometry_msgs::Pose &pose, const Eigen::Quaterniond &q, Ogre::Vector3 p=Ogre::Vector3::ZERO)
void setValue(const geometry_msgs::TransformStamped &tf)
virtual bool getBool() const
virtual int getOptionInt()
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
#define ROS_DEBUG(...)
bool fillPoseStamped(std_msgs::Header &header, geometry_msgs::Pose &pose)


agni_tf_tools
Author(s): Robert Haschke
autogenerated on Mon Jan 9 2023 03:12:02