30 #include <OgreVector3.h> 31 #include <OgreQuaternion.h> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 34 #include <OgreEntity.h> 48 :
MarkerBase(owner, context, parent_node), arrow_(nullptr), last_arrow_set_from_points_(false)
66 ROS_ASSERT(new_message->type == visualization_msgs::Marker::ARROW);
67 ROS_ASSERT(new_message->points.empty() || new_message->points.size() >= 2);
78 Ogre::Vector3 pos, scale;
79 Ogre::Quaternion orient;
80 transform(new_message, pos, orient, scale);
84 arrow_->
setColor(new_message->color.r, new_message->color.g, new_message->color.b,
85 new_message->color.a);
88 if (new_message->points.size() == 2)
92 Ogre::Vector3 point1(new_message->points[0].x, new_message->points[0].y, new_message->points[0].z);
93 Ogre::Vector3 point2(new_message->points[1].x, new_message->points[1].y, new_message->points[1].z);
95 Ogre::Vector3 direction = point2 - point1;
96 float distance = direction.length();
98 float head_length_proportion =
100 float head_length = head_length_proportion * distance;
101 if (new_message->scale.z != 0.0)
103 float length = new_message->scale.z;
104 head_length = std::max<double>(0.0, std::min<double>(length, distance));
106 float shaft_length = distance - head_length;
108 arrow_->
set(shaft_length, new_message->scale.x, head_length, new_message->scale.y);
110 direction.normalise();
113 Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(direction);
128 Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(Ogre::Vector3(1, 0, 0));
Ogre::SceneNode * scene_node_
bool transform(const MarkerConstPtr &message, Ogre::Vector3 &pos, Ogre::Quaternion &orient, Ogre::Vector3 &scale)
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
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.
void extractMaterials(Ogre::Entity *entity, S_MaterialPtr &materials)
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
std::pair< std::string, int32_t > MarkerID
Pure-virtual base class for objects which give Display subclasses context in which to work...
boost::shared_ptr< MarkerSelectionHandler > handler_
S_MaterialPtr getMaterials() override
void onNewMessage(const MarkerConstPtr &old_message, const MarkerConstPtr &new_message) override
DisplayContext * context_
bool last_arrow_set_from_points_
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
visualization_msgs::Marker::ConstPtr MarkerConstPtr
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
Ogre::SceneNode * child_scene_node_
std::set< Ogre::MaterialPtr > S_MaterialPtr
An arrow consisting of a cylinder and a cone.
virtual void setOrientation(const Ogre::Quaternion &orientation)
virtual void setDefaultProportions()
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
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. Values are in the range [0, 1].
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()