Visual.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GAZEBO_RENDERING_VISUAL_HH_
18 #define GAZEBO_RENDERING_VISUAL_HH_
19 
20 #include <boost/enable_shared_from_this.hpp>
21 #include <boost/function.hpp>
22 #include <string>
23 #include <utility>
24 #include <vector>
25 
26 #include <sdf/sdf.hh>
27 #include <ignition/math/Box.hh>
28 #include <ignition/math/Pose3.hh>
29 #include <ignition/math/Quaternion.hh>
30 #include <ignition/math/Vector3.hh>
31 #include <ignition/msgs/MessageTypes.hh>
32 
33 #include "gazebo/common/Color.hh"
34 #include "gazebo/common/Mesh.hh"
35 #include "gazebo/common/Time.hh"
36 
37 #include "gazebo/msgs/MessageTypes.hh"
38 #include "gazebo/math/Box.hh"
39 #include "gazebo/math/Pose.hh"
41 #include "gazebo/math/Vector3.hh"
42 
44 #include "gazebo/util/system.hh"
45 
46 namespace Ogre
47 {
48  class MovableObject;
49  class SceneNode;
50 }
51 
52 namespace gazebo
53 {
54  namespace rendering
55  {
56  class VisualPrivate;
57 
60 
63  class GZ_RENDERING_VISIBLE Visual :
64  public std::enable_shared_from_this<Visual>
65  {
68  public: enum VisualType
69  {
85  VT_PHYSICS
86  };
87 
93  public: Visual(const std::string &_name, VisualPtr _parent,
94  bool _useRTShader = true);
95 
101  public: Visual(const std::string &_name, ScenePtr _scene,
102  bool _useRTShader = true);
103 
105  public: virtual ~Visual();
106 
108  public: void Init();
109 
111  public: virtual void Fini();
112 
117  public: VisualPtr Clone(const std::string &_name, VisualPtr _newParent);
118 
121  public: void LoadFromMsg(ConstVisualPtr &_msg);
122 
125  public: void Load(sdf::ElementPtr _sdf);
126 
128  public: virtual void Load();
129 
131  public: void Update();
132 
139  public: sdf::ElementPtr GetSDF() const;
140 
143  public: void SetName(const std::string &_name);
144 
148  public: std::string GetName() const GAZEBO_DEPRECATED(8.0);
149 
152  public: std::string Name() const;
153 
156  public: void AttachVisual(VisualPtr _vis);
157 
160  public: void DetachVisual(VisualPtr _vis);
161 
164  public: void DetachVisual(const std::string &_name);
165 
168  public: void AttachObject(Ogre::MovableObject *_obj);
169 
172  public: bool HasAttachedObject(const std::string &_name);
173 
176  public: unsigned int GetAttachedObjectCount() const;
177 
179  public: void DetachObjects();
180 
183  public: unsigned int GetChildCount();
184 
189  public: VisualPtr GetChild(unsigned int _index);
190 
198  public: Ogre::MovableObject *AttachMesh(const std::string &_meshName,
199  const std::string &_subMesh="",
200  bool _centerSubmesh = false,
201  const std::string &_objName="");
202 
206  public: void SetScale(const math::Vector3 &_scale) GAZEBO_DEPRECATED(8.0);
207 
210  public: void SetScale(const ignition::math::Vector3d &_scale);
211 
215  public: math::Vector3 GetScale() GAZEBO_DEPRECATED(8.0);
216 
219  public: ignition::math::Vector3d Scale() const;
220 
223  public: ignition::math::Vector3d DerivedScale() const;
224 
227  public: bool GetLighting() const;
228 
231  public: void SetLighting(bool _lighting);
232 
239  public: void SetMaterial(const std::string &_materialName,
240  bool _unique = true, const bool _cascade = true);
241 
245  public: void SetAmbient(const common::Color &_color,
246  const bool _cascade = true);
247 
251  public: void SetDiffuse(const common::Color &_color,
252  const bool _cascade = true);
253 
257  public: void SetSpecular(const common::Color &_color,
258  const bool _cascade = true);
259 
263  public: virtual void SetEmissive(const common::Color &_color,
264  const bool _cascade = true);
265 
268  public: common::Color GetAmbient() const;
269 
272  public: common::Color GetDiffuse() const;
273 
276  public: common::Color GetSpecular() const;
277 
280  public: common::Color GetEmissive() const;
281 
284  public: void SetWireframe(bool _show);
285 
288  public: bool Wireframe() const;
289 
293  private: void SetTransparencyInnerLoop(Ogre::SceneNode *_sceneNode);
294 
298  public: void SetTransparency(float _trans);
299 
302  public: float GetTransparency();
303 
307  public: float DerivedTransparency() const;
308 
311  public: void SetInheritTransparency(const bool _inherit);
312 
315  public: bool InheritTransparency() const;
316 
320  public: virtual void SetHighlighted(bool _highlighted);
321 
325  public: bool GetHighlighted() const;
326 
329  public: bool GetCastShadows() const;
330 
333  public: void SetCastShadows(bool _shadows);
334 
338  public: virtual void SetVisible(bool _visible, bool _cascade = true);
339 
341  public: void ToggleVisible();
342 
345  public: bool GetVisible() const;
346 
350  public: void SetPosition(const math::Vector3 &_pos)
351  GAZEBO_DEPRECATED(8.0);
352 
355  public: void SetPosition(const ignition::math::Vector3d &_pos);
356 
360  public: void SetRotation(const math::Quaternion &_rot)
361  GAZEBO_DEPRECATED(8.0);
362 
365  public: void SetRotation(const ignition::math::Quaterniond &_rot);
366 
370  public: void SetPose(const math::Pose &_pose) GAZEBO_DEPRECATED(8.0);
371 
374  public: void SetPose(const ignition::math::Pose3d &_pose);
375 
379  public: math::Vector3 GetPosition() const GAZEBO_DEPRECATED(8.0);
380 
383  public: ignition::math::Vector3d Position() const;
384 
388  public: math::Quaternion GetRotation() const GAZEBO_DEPRECATED(8.0);
389 
392  public: ignition::math::Quaterniond Rotation() const;
393 
397  public: math::Pose GetPose() const GAZEBO_DEPRECATED(8.0);
398 
402  public: ignition::math::Pose3d Pose() const;
403 
406  public: ignition::math::Pose3d InitialRelativePose() const;
407 
411  public: math::Pose GetWorldPose() const GAZEBO_DEPRECATED(8.0);
412 
415  public: ignition::math::Pose3d WorldPose() const;
416 
420  public: void SetWorldPose(const math::Pose &_pose) GAZEBO_DEPRECATED(8.0);
421 
424  public: void SetWorldPose(const ignition::math::Pose3d &_pose);
425 
429  public: void SetWorldPosition(const math::Vector3 &_pos)
430  GAZEBO_DEPRECATED(8.0);
431 
434  public: void SetWorldPosition(const ignition::math::Vector3d &_pos);
435 
439  public: void SetWorldRotation(const math::Quaternion &_rot)
440  GAZEBO_DEPRECATED(8.0);
441 
444  public: void SetWorldRotation(const ignition::math::Quaterniond &_rot);
445 
448  public: Ogre::SceneNode *GetSceneNode() const;
449 
451  public: void MakeStatic();
452 
455  public: bool IsStatic() const;
456 
459  public: void EnableTrackVisual(VisualPtr _vis);
460 
462  public: void DisableTrackVisual();
463 
466  public: std::string GetNormalMap() const;
467 
470  public: void SetNormalMap(const std::string &_nmap);
471 
476  public: void SetRibbonTrail(bool _value,
477  const common::Color &_initialColor,
478  const common::Color &_changeColor);
479 
483  public: math::Box GetBoundingBox() const GAZEBO_DEPRECATED(8.0);
484 
487  public: ignition::math::Box BoundingBox() const;
488 
492  public: DynamicLines *CreateDynamicLine(
493  RenderOpType _type = RENDERING_LINE_STRIP);
494 
497  public: void DeleteDynamicLine(DynamicLines *_line);
498 
502  public: void AttachLineVertex(DynamicLines *_line,
503  unsigned int _index);
504 
507  public: std::string GetMaterialName() const;
508 
513  public: void InsertMesh(const std::string &_meshName,
514  const std::string &_subMesh = "",
515  bool _centerSubmesh = false);
516 
521  public: static void InsertMesh(const common::Mesh *_mesh,
522  const std::string &_subMesh = "",
523  bool _centerSubmesh = false);
524 
527  public: void UpdateFromMsg(ConstVisualPtr &_msg);
528 
531  public: bool IsPlane() const;
532 
535  public: VisualPtr GetParent() const;
536 
540  public: VisualPtr GetRootVisual();
541 
548  public: VisualPtr GetNthAncestor(unsigned int _n);
549 
553  public: bool IsAncestorOf(const rendering::VisualPtr _visual) const;
554 
558  public: bool IsDescendantOf(const rendering::VisualPtr _visual) const;
559 
563  public: unsigned int GetDepth() const;
564 
568  public: std::string GetShaderType() const;
569 
573  public: void SetShaderType(const std::string &_type);
574 
579  public: void MoveToPosition(const math::Pose &_pose, double _time)
580  GAZEBO_DEPRECATED(8.0);
581 
585  public: void MoveToPosition(const ignition::math::Pose3d &_pose,
586  const double _time);
587 
593  public: void MoveToPositions(const std::vector<math::Pose> &_pts,
594  double _time,
595  std::function<void()> _onComplete = nullptr)
596  GAZEBO_DEPRECATED(8.0);
597 
602  public: void MoveToPositions(
603  const std::vector<ignition::math::Pose3d> &_pts, const double _time,
604  std::function<void()> _onComplete = nullptr);
605 
611  public: void SetVisibilityFlags(uint32_t _flags);
612 
618  public: uint32_t GetVisibilityFlags();
619 
621  public: void ShowBoundingBox();
622 
626  public: void ShowCollision(bool _show);
627 
630  public: void ShowSkeleton(bool _show);
631 
634  public: void SetScene(ScenePtr _scene);
635 
638  public: ScenePtr GetScene() const;
639 
642  public: void ShowJoints(bool _show);
643 
646  public: void ShowCOM(bool _show);
647 
650  public: void ShowInertia(bool _show);
651 
654  public: void ShowLinkFrame(bool _show);
655 
658  public: void SetSkeletonPose(const msgs::PoseAnimation &_pose);
659 
664  public: void LoadPlugin(const std::string &_filename,
665  const std::string &_name,
666  sdf::ElementPtr _sdf);
667 
670  public: void RemovePlugin(const std::string &_name);
671 
673  public: uint32_t GetId() const;
674 
676  public: void SetId(uint32_t _id);
677 
680  public: std::string GetGeometryType() const;
681 
684  public: ignition::math::Vector3d GetGeometrySize() const;
685 
688  public: std::string GetMeshName() const;
689 
693  public: std::string GetSubMeshName() const;
694 
696  public: void ClearParent();
697 
701  public: void ToggleLayer(const int32_t _layer);
702 
705  public: void SetLayer(const int32_t _layer);
706 
709  public: Visual::VisualType GetType() const;
710 
713  public: void SetType(const Visual::VisualType _type);
714 
717  public: bool UseRTShader() const;
718 
722  public: void SetTypeMsg(const google::protobuf::Message *_msg);
723 
728  public: void AddPendingChild(std::pair<VisualType,
729  const google::protobuf::Message *> _pair);
730 
734  public: static Visual::VisualType ConvertVisualType(
735  const msgs::Visual::Type &_type);
736 
740  public: static msgs::Visual::Type ConvertVisualType(
741  const Visual::VisualType &_type);
742 
746  public: void FillMaterialMsg(ignition::msgs::Material &_msg) const;
747 
755  protected: Visual(VisualPrivate &_dataPtr,
756  const std::string &_name, VisualPtr _parent,
757  bool _useRTShader = true);
758 
766  protected: Visual(VisualPrivate &_dataPtr,
767  const std::string &_name, ScenePtr _scene,
768  bool _useRTShader = true);
769 
772  protected: void ProcessMaterialMsg(const ignition::msgs::Material &_msg);
773 
780  private: void Init(const std::string &_name, ScenePtr _scene,
781  bool _useRTShader);
782 
789  private: void Init(const std::string &_name, VisualPtr _parent,
790  bool _useRTShader);
791 
794  private: void LoadPlugins();
795 
796  private: void LoadPlugin(sdf::ElementPtr _sdf);
797 
801  private: void BoundsHelper(Ogre::SceneNode *_node,
802  ignition::math::Box &_box) const;
803 
807  private: bool GetCenterSubMesh() const;
808 
811  private: void DestroyAllAttachedMovableObjects(
812  Ogre::SceneNode *_sceneNode);
813 
817  private: void UpdateGeomSize(const ignition::math::Vector3d &_scale);
818 
821  private: void UpdateTransparency(const bool _cascade = true);
822 
825  protected: VisualPrivate *dataPtr;
826  };
828  }
829 }
830 #endif
Class for drawing lines that can change.
Definition: DynamicLines.hh:37
Link visual.
Definition: Visual.hh:75
Entity visual.
Definition: Visual.hh:71
GUI visual.
Definition: Visual.hh:83
A renderable object.
Definition: Visual.hh:63
RenderOpType
Type of render operation for a drawable.
Definition: RenderTypes.hh:211
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:81
Model visual.
Definition: Visual.hh:73
std::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:113
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
Visual visual.
Definition: Visual.hh:77
Collision visual.
Definition: Visual.hh:79
Sensor visual.
Definition: Visual.hh:81