MultiRobotInfoDisplay.cpp
Go to the documentation of this file.
2 
32 #include <OGRE/OgreSceneNode.h>
33 #include <OGRE/OgreSceneManager.h>
34 
35 #include <tf/transform_listener.h>
36 
40 #include <rviz/frame_manager.h>
41 
44 
45 namespace tuw_multi_robot_rviz {
46 
47 // The constructor must have no arguments, so we can't give the
48 // constructor the parameters it needs to fully initialize.
50  nh_ = ros::NodeHandle("");
52 
53  property_scale_pose_.reset(new rviz::FloatProperty ( "Scale Pose", 0.4,
54  "Scale of the pose's pose.",
55  this, SLOT ( updateScalePose() ) ));
56  property_scale_pose_->setMin ( 0 );
57  property_scale_pose_->setMax ( 10 );
58 
59  property_color_pose_.reset(new rviz::ColorProperty ( "Color Pose", QColor ( 204, 51, 0 ),
60  "Color to draw the pose's pose.",
61  this, SLOT ( updateColorPose())));
62 
63  keep_alive_.reset(new rviz::IntProperty("Keep Alive (s)",
64  5,
65  "The amount of seconds in which a robot is still displayed after it does not publish anymore. This value should be greater or equal than 1.",
66  this,
67  SLOT(onKeepAliveChanged()),
68  this));
69  keep_alive_->setMin(1);
70  keep_alive_->setMax(20);
71  keep_measurements_.reset(new rviz::IntProperty("Keep Measurements",
72  5,
73  "The number of pose measurements that should be kept for each robot. Make sure that it is greater than 0.",
74  this,
76  this));
77  keep_measurements_->setMin(1);
78  keep_measurements_->setMax(10000);
79 
80  robot_bool_properties_.reset(new rviz::Property("Robots",
81  QVariant(),
82  "A tree view of all the available robots",
83  this));
84 }
85 
86 void MultiRobotInfoDisplay::callbackRobotInfo(const tuw_multi_robot_msgs::RobotInfoConstPtr &msg )
87 {
88  if (!visual_) return;
89 
90  ros::Time tic = ros::Time::now();
91  // Here we call the rviz::FrameManager to get the transform from the
92  // fixed frame to the frame in the header of this Imu message. If
93  // it fails, we can't do anything else so we return.
94  Ogre::Quaternion orientation(1.0,0.0,0.0,0.0);
95  Ogre::Vector3 position(0,0,0);
96 
97  if ( !context_->getFrameManager()->getTransform ( msg->header.frame_id, msg->header.stamp, position, orientation ) ) {
98  ROS_DEBUG ( "Error transforming from frame '%s' to frame '%s'",
99  msg->header.frame_id.c_str(), qPrintable ( fixed_frame_ ) );
100  return;
101  }
102 
103  // Now set or update the contents of the visual.
104  visual_->setMessage ( msg );
105  //visual_->setFramePosition ( position );
106  //visual_->setFrameOrientation ( orientation );
107  //visual_->setScalePose ( property_scale_pose_->getFloat() );
108  //visual_->setColorPose ( property_color_pose_->getOgreColor() );
109 
110  //auto dur = ros::Time::now() - tic;
111  auto it = bool_properties_.find(msg->robot_name);
112  if (it == bool_properties_.end())
113  {
114  std::unique_ptr<rviz::BoolProperty> bp;
115  bp.reset(new rviz::BoolProperty(QString(msg->robot_name.c_str()),
116  true,
117  QString("display this robot?"),
119  SLOT(updateBoolProperty()),
120  this));
121  bool_properties_.insert(std::pair<std::string,std::unique_ptr<rviz::BoolProperty>>(msg->robot_name, std::move(bp)));
122  }
123 
124 }
125 // After the top-level rviz::Display::initialize() does its own setup,
126 // it calls the subclass's onInitialize() function. This is where we
127 // instantiate all the workings of the class. We make sure to also
128 // call our immediate super-class's onInitialize() function, since it
129 // does important stuff setting up the message filter.
130 //
131 // Note that "MFDClass" is a typedef of
132 // ``MessageFilterDisplay<message type>``, to save typing that long
133 // templated class name every time you need to refer to the
134 // superclass.
138 }
139 
141 }
142 
143 // Clear the visual by deleting its object.
145  MFDClass::reset();
146 }
147 
148 // Set the current scale for the visual's pose.
150  float scale = property_scale_pose_->getFloat();
151  visual_->setScalePose ( scale );
152 }
153 
154 // Set the current color for the visual's pose.
156  Ogre::ColourValue color = property_color_pose_->getOgreColor();
157  visual_->setColorPose ( color );
158 }
159 
161 {
162  if (!visual_) return;
163  for (const auto &it : bool_properties_)
164  {
165  if(!it.second->getBool())
166  {
167  visual_->disableRobot(it.first);
168  } else {
169  visual_->enableRobot(it.first);
170  }
171  }
172 }
173 
175 {
176  if (!visual_) return;
177  visual_->resetDuration(ros::Duration(keep_measurements_->getInt(),0));
178 }
179 
181 {
182  if (!visual_) return;
183  visual_->resetKeepMeasurementsCount(keep_alive_->getInt());
184 }
185 
186 // This is our callback to handle an incoming message.
187 void MultiRobotInfoDisplay::processMessage (const tuw_multi_robot_msgs::RobotInfoConstPtr &msg ) {
188 }
189 
190 } // end namespace tuw_geometry_rviz
191 
192 // Tell pluginlib about this class. It is important to do this in
193 // global scope, outside our package's namespace.
tuw_multi_robot_rviz::MultiRobotInfoVisual
Definition: MultiRobotInfoVisual.h:189
rviz::MessageFilterDisplay::reset
void reset() override
tuw_multi_robot_rviz::MultiRobotInfoDisplay::~MultiRobotInfoDisplay
virtual ~MultiRobotInfoDisplay()
Definition: MultiRobotInfoDisplay.cpp:140
tuw_multi_robot_rviz::MultiRobotInfoDisplay::sub_robot_info_
ros::Subscriber sub_robot_info_
Definition: MultiRobotInfoDisplay.h:85
rviz::BoolProperty
frame_manager.h
tuw_multi_robot_rviz
Definition: MultiRobotGoalSelector.h:61
MultiRobotInfoVisual.h
tuw_multi_robot_rviz::MultiRobotInfoDisplay::robot_bool_properties_
std::shared_ptr< rviz::Property > robot_bool_properties_
Definition: MultiRobotInfoDisplay.h:79
rviz::Display::fixed_frame_
QString fixed_frame_
tuw_multi_robot_rviz::MultiRobotInfoDisplay::reset
virtual void reset()
Definition: MultiRobotInfoDisplay.cpp:144
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const=0
float_property.h
rviz::ColorProperty
visualization_manager.h
rviz::Display
tuw_multi_robot_rviz::MultiRobotInfoDisplay::onKeepAliveChanged
void onKeepAliveChanged()
Definition: MultiRobotInfoDisplay.cpp:174
rviz::FloatProperty
rviz::Property
class_list_macros.h
tuw_multi_robot_rviz::MultiRobotInfoDisplay::onKeepMeasurementsChanged
void onKeepMeasurementsChanged()
Definition: MultiRobotInfoDisplay.cpp:180
tuw_multi_robot_rviz::MultiRobotInfoDisplay::property_scale_pose_
std::shared_ptr< rviz::FloatProperty > property_scale_pose_
Definition: MultiRobotInfoDisplay.h:82
tuw_multi_robot_rviz::MultiRobotInfoDisplay::callbackRobotInfo
void callbackRobotInfo(const tuw_multi_robot_msgs::RobotInfoConstPtr &msg)
Definition: MultiRobotInfoDisplay.cpp:86
tuw_multi_robot_rviz::MultiRobotInfoDisplay::processMessage
void processMessage(const tuw_multi_robot_msgs::RobotInfoConstPtr &msg)
Definition: MultiRobotInfoDisplay.cpp:187
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ROS_DEBUG
#define ROS_DEBUG(...)
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
tuw_multi_robot_rviz::MultiRobotInfoDisplay::updateColorPose
void updateColorPose()
Definition: MultiRobotInfoDisplay.cpp:155
tuw_multi_robot_rviz::MultiRobotInfoDisplay::updateBoolProperty
void updateBoolProperty()
Definition: MultiRobotInfoDisplay.cpp:160
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const=0
tuw_multi_robot_rviz::MultiRobotInfoDisplay::updateScalePose
void updateScalePose()
Definition: MultiRobotInfoDisplay.cpp:149
transform_listener.h
rviz::MessageFilterDisplay::onInitialize
void onInitialize() override
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
tuw_multi_robot_rviz::MultiRobotInfoDisplay::nh_
ros::NodeHandle nh_
Definition: MultiRobotInfoDisplay.h:86
rviz::Display::context_
DisplayContext * context_
ros::Time
tuw_multi_robot_rviz::MultiRobotInfoDisplay::onInitialize
virtual void onInitialize()
Definition: MultiRobotInfoDisplay.cpp:135
tuw_multi_robot_rviz::MultiRobotInfoDisplay::visual_
std::shared_ptr< MultiRobotInfoVisual > visual_
Definition: MultiRobotInfoDisplay.h:76
tuw_multi_robot_rviz::MultiRobotInfoDisplay::keep_alive_
std::shared_ptr< rviz::IntProperty > keep_alive_
Definition: MultiRobotInfoDisplay.h:81
MultiRobotInfoDisplay.h
tuw_multi_robot_rviz::MultiRobotInfoDisplay::bool_properties_
std::map< std::string, std::shared_ptr< rviz::BoolProperty > > bool_properties_
Definition: MultiRobotInfoDisplay.h:84
tuw_multi_robot_rviz::MultiRobotInfoDisplay::keep_measurements_
std::shared_ptr< rviz::IntProperty > keep_measurements_
Definition: MultiRobotInfoDisplay.h:80
tuw_multi_robot_rviz::MultiRobotInfoDisplay::property_color_pose_
std::shared_ptr< rviz::ColorProperty > property_color_pose_
Definition: MultiRobotInfoDisplay.h:83
tuw_multi_robot_rviz::MultiRobotInfoDisplay::MultiRobotInfoDisplay
MultiRobotInfoDisplay()
Definition: MultiRobotInfoDisplay.cpp:49
ros::Duration
tuw_multi_robot_rviz::MultiRobotInfoDisplay
Definition: MultiRobotInfoDisplay.h:41
color_property.h
ros::NodeHandle
rviz::IntProperty
ros::Time::now
static Time now()


tuw_multi_robot_rviz
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:10:08