arrow_marker.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
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 
31 #include <OgreQuaternion.h>
32 #include <OgreSceneNode.h>
33 #include <OgreSceneManager.h>
34 #include <OgreEntity.h>
35 
38 #include <rviz/display_context.h>
42 
44 
45 namespace rviz
46 {
47 ArrowMarker::ArrowMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node)
48  : MarkerBase(owner, context, parent_node), arrow_(nullptr), last_arrow_set_from_points_(false)
49 {
50  child_scene_node_ = scene_node_->createChildSceneNode();
51 }
52 
54 {
55  delete arrow_;
56  context_->getSceneManager()->destroySceneNode(child_scene_node_);
57 }
58 
60 {
61  arrow_->set(0.77, 1.0, 0.23, 2.0);
62 }
63 
64 void ArrowMarker::onNewMessage(const MarkerConstPtr& /*old_message*/, const MarkerConstPtr& new_message)
65 {
66  ROS_ASSERT(new_message->type == visualization_msgs::Marker::ARROW);
67  ROS_ASSERT(new_message->points.empty() || new_message->points.size() >= 2);
68 
69  if (!arrow_)
70  {
73  handler_.reset(
74  new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id), context_));
75  handler_->addTrackedObjects(arrow_->getSceneNode());
76  }
77 
78  Ogre::Vector3 pos, scale;
79  Ogre::Quaternion orient;
80  if (!transform(new_message, pos, orient, scale))
81  {
82  scene_node_->setVisible(false);
83  return;
84  }
85 
86  scene_node_->setVisible(true);
87  setPosition(pos);
88  setOrientation(orient);
89 
90  arrow_->setColor(new_message->color.r, new_message->color.g, new_message->color.b,
91  new_message->color.a);
92 
93  // compute translation & rotation from the two points
94  if (new_message->points.size() == 2)
95  {
97 
98  Ogre::Vector3 point1(new_message->points[0].x, new_message->points[0].y, new_message->points[0].z);
99  Ogre::Vector3 point2(new_message->points[1].x, new_message->points[1].y, new_message->points[1].z);
100 
101  Ogre::Vector3 direction = point2 - point1;
102  float distance = direction.length();
103 
104  float head_length_proportion =
105  0.23; // Seems to be a good value based on default in arrow.h of shaft:head ratio of 1:0.3
106  float head_length = head_length_proportion * distance;
107  if (new_message->scale.z != 0.0)
108  {
109  float length = new_message->scale.z;
110  head_length = std::max<double>(0.0, std::min<double>(length, distance)); // clamp
111  }
112  float shaft_length = distance - head_length;
113 
114  arrow_->set(shaft_length, new_message->scale.x, head_length, new_message->scale.y);
115 
116  direction.normalise();
117 
118  // for some reason the arrow goes into the y direction by default
119  Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(direction);
120 
121  arrow_->setPosition(point1);
122  arrow_->setOrientation(orient);
123  }
124  else
125  {
127  {
128  // Reset arrow to default proportions if we previously set it from points
131  }
132  arrow_->setScale(scale);
133 
134  Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(Ogre::Vector3(1, 0, 0));
135  arrow_->setOrientation(orient);
136  }
137 }
138 
140 {
141  S_MaterialPtr materials;
142  extractMaterials(arrow_->getHead()->getEntity(), materials);
143  extractMaterials(arrow_->getShaft()->getEntity(), materials);
144  return materials;
145 }
146 
147 } // namespace rviz
rviz::Arrow::set
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
Definition: arrow.cpp:74
rviz::MarkerBase::context_
DisplayContext * context_
Definition: marker_base.h:108
shape.h
rviz::S_MaterialPtr
std::set< Ogre::MaterialPtr > S_MaterialPtr
Definition: marker_base.h:51
rviz::MarkerDisplay
Displays "markers" sent in by other ROS nodes on the "visualization_marker" topic.
Definition: marker_display.h:70
marker_selection_handler.h
rviz::MarkerBase::setPosition
virtual void setPosition(const Ogre::Vector3 &position)
Definition: marker_base.cpp:124
rviz::Arrow
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:57
rviz::MarkerBase
Definition: marker_base.h:53
rviz::Arrow::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
Definition: arrow.cpp:119
marker_display.h
rviz::MarkerBase::scene_node_
Ogre::SceneNode * scene_node_
Definition: marker_base.h:110
rviz::MarkerBase::setOrientation
virtual void setOrientation(const Ogre::Quaternion &orientation)
Definition: marker_base.cpp:129
rviz::MarkerBase::handler_
boost::shared_ptr< MarkerSelectionHandler > handler_
Definition: marker_base.h:116
selection_manager.h
rviz::Arrow::getShaft
Shape * getShaft()
Definition: arrow.h:157
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
rviz::ArrowMarker::onNewMessage
void onNewMessage(const MarkerConstPtr &old_message, const MarkerConstPtr &new_message) override
Definition: arrow_marker.cpp:64
rviz::ArrowMarker::getMaterials
S_MaterialPtr getMaterials() override
Definition: arrow_marker.cpp:139
rviz::MarkerBase::transform
bool transform(const MarkerConstPtr &message, Ogre::Vector3 &pos, Ogre::Quaternion &orient, Ogre::Vector3 &scale)
Definition: marker_base.cpp:87
rviz
Definition: add_display_dialog.cpp:54
rviz::Arrow::getHead
Shape * getHead()
Definition: arrow.h:161
rviz::ArrowMarker::arrow_
Arrow * arrow_
Definition: arrow_marker.h:56
rviz::MarkerSelectionHandler
Definition: marker_selection_handler.h:45
arrow.h
ogre_vector.h
rviz::Shape::getEntity
Ogre::Entity * getEntity()
Definition: shape.h:110
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::ArrowMarker::last_arrow_set_from_points_
bool last_arrow_set_from_points_
Definition: arrow_marker.h:59
rviz::ArrowMarker::setDefaultProportions
virtual void setDefaultProportions()
Definition: arrow_marker.cpp:59
arrow_marker.h
rviz::ArrowMarker::~ArrowMarker
~ArrowMarker() override
Definition: arrow_marker.cpp:53
rviz::MarkerID
std::pair< std::string, int32_t > MarkerID
Definition: interactive_marker_display.h:58
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
display_context.h
rviz::ArrowMarker::ArrowMarker
ArrowMarker(MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node)
Definition: arrow_marker.cpp:47
rviz::Arrow::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
Definition: arrow.cpp:114
rviz::Arrow::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
Definition: arrow.h:147
rviz::MarkerBase::extractMaterials
void extractMaterials(Ogre::Entity *entity, S_MaterialPtr &materials)
Definition: marker_base.cpp:144
rviz::Arrow::setColor
void setColor(float r, float g, float b, float a) override
Set the color of this arrow. Sets both the head and shaft color to the same value....
Definition: arrow.cpp:89
ROS_ASSERT
#define ROS_ASSERT(cond)
rviz::MarkerBase::MarkerConstPtr
visualization_msgs::Marker::ConstPtr MarkerConstPtr
Definition: marker_base.h:57
rviz::ArrowMarker::child_scene_node_
Ogre::SceneNode * child_scene_node_
Definition: arrow_marker.h:57
rviz::Arrow::setScale
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
Definition: arrow.cpp:134


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:52