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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:50