29 #ifndef MULTI_ROBOT_GOAL_SELECTOR_H 30 #define MULTI_ROBOT_GOAL_SELECTOR_H 42 #include <geometry_msgs/Pose.h> 57 class VisualizationManager;
58 class ViewportMouseEvent;
75 virtual void onInitialize();
77 virtual void activate();
78 virtual void deactivate();
83 void onRobotNrChanged();
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);
120 #endif // PLANT_FLAG_TOOL_H std::vector< std::unique_ptr< rviz::Arrow > > arrows_robot2flag_
rviz::Property * group_robot_names_
std::vector< double > flag_angles_
std::string flag_resource_
TFSIMD_FORCE_INLINE Vector3()
std::vector< Ogre::Vector3 > flag_positions_
std::unique_ptr< rviz::Arrow > arrow_
std::vector< Ogre::SceneNode * > flag_nodes_
Ogre::SceneNode * moving_flag_node_
rviz::Property * group_robot_goals_
rviz::VectorProperty * current_flag_property_
rviz::IntProperty * nr_robots_
std::vector< rviz::StringProperty * > robot_names_
std::unique_ptr< rviz::Arrow > arrow_robot2flag_