50 namespace vm = visualization_msgs;
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();
65 pose.position.x = p.x;
66 pose.position.y = p.y;
67 pose.position.z = p.z;
72 :
rviz::Display(), tf_callback_handle_(0), tf_request_handle_(0), ignore_updates_(false) {
81 "Adapt transformation when changing the parent frame? " 82 "If so, the marker will not move.",
101 "Choose which type of interactive marker to show",
this,
117 Display::onInitialize();
139 Display::onDisable();
148 Display::update(wall_dt, ros_dt);
158 static vm::Marker
createArrowMarker(
double scale,
const Eigen::Vector3d& dir,
const QColor& color) {
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;
166 updatePose(marker.pose, Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitX(), dir));
168 marker.color.r = color.redF();
169 marker.color.g = color.greenF();
170 marker.color.b = color.blueF();
171 marker.color.a = color.alphaF();
176 inline void setOrientation(geometry_msgs::Quaternion& q,
double w,
double x,
double y,
double z) {
186 vm::InteractiveMarkerControl ctrl;
188 ctrl.always_visible =
true;
190 ctrl.orientation_mode = vm::InteractiveMarkerControl::VIEW_FACING;
191 ctrl.independent_marker_orientation =
true;
192 ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_ROTATE_3D;
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")));
200 im.controls.push_back(ctrl);
204 vm::InteractiveMarkerControl ctrl;
205 ctrl.always_visible =
false;
208 ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
210 im.controls.push_back(ctrl);
211 ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
213 im.controls.push_back(ctrl);
216 ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
218 im.controls.push_back(ctrl);
219 ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
221 im.controls.push_back(ctrl);
224 ctrl.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
226 im.controls.push_back(ctrl);
227 ctrl.interaction_mode = vm::InteractiveMarkerControl::ROTATE_AXIS;
229 im.controls.push_back(ctrl);
241 vm::InteractiveMarker im;
249 else if (type ==
DOF6) {
268 imarker_->setShowDescription(
false);
299 header.frame_id = parent_frame;
306 Ogre::Vector3 p = Ogre::Vector3::ZERO;
307 Ogre::Quaternion q = Ogre::Quaternion::IDENTITY;
310 tf = Eigen::Translation3d(p.x, p.y, p.z) * Eigen::Quaterniond(q.w, q.x, q.y, q.z);
316 Eigen::Affine3d prevRef, nextRef;
322 Eigen::Affine3d newPose = nextRef.inverse() * prevRef * curPose;
323 Eigen::Vector3d
t = newPose.translation();
343 vm::InteractiveMarkerPose marker_pose;
345 imarker_->processMessage(marker_pose);
348 geometry_msgs::TransformStamped
tf;
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;
364 vm::InteractiveMarkerPose marker_pose;
366 imarker_->processMessage(marker_pose);
375 if (feedback.event_type != vm::InteractiveMarkerFeedback::POSE_UPDATE)
379 geometry_msgs::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(),
391 const geometry_msgs::Point& p = pose.position;
392 const geometry_msgs::Quaternion& q = pose.orientation;
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
std::string getFrameStd() const
virtual bool setVector(const Ogre::Vector3 &vector)
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
DisplayContext * context_
virtual Ogre::Vector3 getVector() const
INTERACTIVE_MARKERS_PUBLIC void autoComplete(visualization_msgs::InteractiveMarker &msg, bool enable_autocomplete_transparency=true)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
geometry_msgs::TransformStamped t
bool setFloat(float new_value)
virtual void addOption(const QString &option, int value=0)
Ogre::SceneNode * getSceneNode() const
virtual FrameManager * getFrameManager() const=0
void userFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
virtual std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const=0
static const QString FIXED_FRAME_STRING
virtual float getFloat() const
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)
virtual bool getBool() const
virtual int getOptionInt()
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)