MultiRobotGoalSelector.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, 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 #ifndef MULTI_ROBOT_GOAL_SELECTOR_H
30 #define MULTI_ROBOT_GOAL_SELECTOR_H
31 
32 #include <rviz/tool.h>
33 #include <ros/ros.h>
39 #include <memory>
40 #include "TextVisual.h"
41 
42 #include <geometry_msgs/Pose.h>
43 
44 namespace Ogre
45 {
46 class SceneNode;
47 class Vector3;
48 class Quaternion;
49 }
50 
51 namespace rviz
52 {
53 class VectorProperty;
54 class IntProperty;
55 class FloatProperty;
56 class StringProperty;
57 class VisualizationManager;
58 class ViewportMouseEvent;
59 }
60 
62 {
63 
64 // BEGIN_TUTORIAL
65 // Here we declare our new subclass of rviz::Tool. Every tool
66 // which can be added to the tool bar is a subclass of
67 // rviz::Tool.
69 {
70 Q_OBJECT
71 public:
74 
75  virtual void onInitialize();
76 
77  virtual void activate();
78  virtual void deactivate();
79 
80  virtual int processMouseEvent( rviz::ViewportMouseEvent& event );
81 
82 protected Q_SLOTS:
83  void onRobotNrChanged();
84 
85 private:
86  enum state {
88  Orientation
89  };
90 
91  void make_quaternion(geometry_msgs::Pose::_orientation_type &q, double pitch, double roll, double yaw);
92  void make_quaternion(Ogre::Quaternion &q, double pitch, double roll, double yaw);
93  void makeFlag( const Ogre::Vector3& position, const Ogre::Quaternion &orientation);
94 
97  std::vector<Ogre::SceneNode*> flag_nodes_;
98  Ogre::SceneNode* moving_flag_node_;
99  std::string flag_resource_;
102  std::vector<rviz::StringProperty*> robot_names_;
105  std::unique_ptr<rviz::Arrow> arrow_;
106  std::unique_ptr<rviz::Arrow> arrow_robot2flag_;
108  std::vector<double> flag_angles_;
109  std::vector<std::unique_ptr<rviz::Arrow>> arrows_robot2flag_;
110  std::vector<Ogre::Vector3> flag_positions_;
111 
112  uint32_t currentRobotNr_;
113  uint32_t maxRobots_;
114  uint32_t robotCount_;
115 };
116 // END_TUTORIAL
117 
118 } // end namespace rviz_plugin_tutorials
119 
120 #endif // PLANT_FLAG_TOOL_H
std::vector< std::unique_ptr< rviz::Arrow > > arrows_robot2flag_
TFSIMD_FORCE_INLINE Vector3()
std::vector< Ogre::SceneNode * > flag_nodes_
std::vector< rviz::StringProperty * > robot_names_


tuw_multi_robot_rviz
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:40