ObjectDetectionVisual.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2017 by Florian Beck <florian.beck@tuwien.ac.at> *
4  * *
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above copyright *
10  * notice, this list of conditions and the following disclaimer. *
11  * 2. Redistributions in binary form must reproduce the above copyright *
12  * notice, this list of conditions and the following disclaimer in *
13  * the documentation and/or other materials provided with the *
14  * distribution. *
15  * 3. Neither the name of the copyright holder nor the names of its *
16  * contributors may be used to endorse or promote products derived *
17  * from this software without specific prior written permission. *
18  * *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS *
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE *
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, *
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, *
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY *
29  * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE *
30  * POSSIBILITY OF SUCH DAMAGE. *
31  ***************************************************************************/
32 
33 #include <ros/ros.h>
34 
35 #include <OGRE/OgreVector3.h>
36 #include <OGRE/OgreMatrix3.h>
37 #include <OGRE/OgreSceneNode.h>
38 #include <OGRE/OgreSceneManager.h>
39 
41 
42 namespace tuw_object_rviz
43 {
44 ObjectDetectionVisual::ObjectDetectionVisual(Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node)
45 {
46  scene_manager_ = scene_manager;
47 
48  // Ogre::SceneNode s form a tree, with each node storing the
49  // transform (position and orientation) of itself relative to its
50  // parent. Ogre does the math of combining those transforms when it
51  // is time to render.
52  //
53  // Here we create a node to store the pose of the MarkerDetection's header frame
54  // relative to the RViz fixed frame.
55  frame_node_ = parent_node->createChildSceneNode();
56 
57  // We create the visual objects within the frame node so that we can
58  // set thier position and direction relative to their header frame.
62  detection_id_.reset(new TextVisual(scene_manager_, frame_node_, Ogre::Vector3(0, 0, 0)));
63 }
64 
66 {
67  // Destroy the frame node since we don't need it anymore.
68  scene_manager_->destroySceneNode(frame_node_);
69 }
70 
71 void ObjectDetectionVisual::setMessage(const tuw_object_msgs::ObjectWithCovariance::ConstPtr& msg)
72 {
73  Ogre::Vector3 position =
74  Ogre::Vector3(msg->object.pose.position.x, msg->object.pose.position.y, msg->object.pose.position.z);
75  position = transform_ * position;
76  position.z = 0; // fix on ground z=0
77 
78  Ogre::Vector3 vel = Ogre::Vector3(msg->object.twist.linear.x, msg->object.twist.linear.y, msg->object.twist.linear.z);
79 
80  Ogre::Quaternion orientation = Ogre::Quaternion(msg->object.pose.orientation.w, msg->object.pose.orientation.x,
81  msg->object.pose.orientation.y, msg->object.pose.orientation.z);
82 
83  if(msg->covariance_pose.size() == 9)
84  {
85  covariance_->setVisible(true);
86  Ogre::Matrix3 C = Ogre::Matrix3(msg->covariance_pose[0], msg->covariance_pose[1], msg->covariance_pose[2],
87  msg->covariance_pose[3], msg->covariance_pose[4], msg->covariance_pose[5],
88  msg->covariance_pose[6], msg->covariance_pose[7], msg->covariance_pose[8]);
89 
90  // rotate covariance matrix in right coordinates
91  // cov(Ax) = A * cov(x) * AT
92  Ogre::Matrix3 rotation_mat;
93  transform_.extract3x3Matrix(rotation_mat);
94  C = rotation_mat * C * rotation_mat.Transpose();
95 
96  covariance_->setOrientation(orientation);
97  covariance_->setPosition(position);
98  covariance_->setMeanCovariance(Ogre::Vector3(0, 0, 0), C);
99  covariance_->setLineWidth(0.05);
100  }
101  else
102  {
103  covariance_->setVisible(false);
104  ROS_WARN("Covariance is not 9x9 won't display");
105  }
106 
107  pose_->setPosition(position);
108  pose_->setDirection(vel);
109 
110  pose_->setScale(Ogre::Vector3(0.02 * position.distance(vel), 0.5, 0.5));
111 
112  // only show arrow if velocity > 0 (in any direction)
113  /*
114  if (vel == Ogre::Vector3::ZERO)
115  {
116  pose_->getSceneNode()->setVisible(false, true);
117  }
118  else
119  {
120  pose_->getSceneNode()->setVisible(true, true);
121  }*/
122 
123  mean_->setPosition(position);
124  mean_->setScale(Ogre::Vector3(0.1, 0.1, 0.1));
125 
126  detection_id_->setPosition(position - Ogre::Vector3(0, 0, 0.2));
127  detection_id_->setCharacterHeight(0.2);
128 
129  // concatenate ids with confidences as string for display
130  // only first two decimal digits are displayed for confidences
131  std::string ids = "";
132  std::vector<int>::const_iterator it_ids = msg->object.ids.begin();
133  std::vector<double>::const_iterator it_conf = msg->object.ids_confidence.begin();
134 
135  for (; (it_ids != msg->object.ids.end()) || (it_conf != msg->object.ids_confidence.end()); it_ids++, it_conf++)
136  {
137  std::string conf = (boost::format("%.2f") % *it_conf).str();
138 
139  if (it_ids == (msg->object.ids.end() - 1))
140  {
141  ids += boost::lexical_cast<std::string>(*it_ids) + " (" + conf + ")";
142  }
143  else
144  {
145  ids += boost::lexical_cast<std::string>(*it_ids) + " (" + conf + ")" + ", ";
146  }
147  }
148 
149  detection_id_->setCaption(ids);
150 }
151 
152 // Position is passed through to the SceneNode.
153 void ObjectDetectionVisual::setFramePosition(const Ogre::Vector3& position)
154 {
155  frame_node_->setPosition(position);
156 }
157 
158 // Orientation is passed through to the SceneNode.
159 void ObjectDetectionVisual::setFrameOrientation(const Ogre::Quaternion& orientation)
160 {
161  frame_node_->setOrientation(orientation);
162 }
163 
164 void ObjectDetectionVisual::setTransform(const Ogre::Vector3& position, const Ogre::Quaternion& orientation)
165 {
166  transform_ = Ogre::Matrix4(orientation);
167  transform_.setTrans(position);
168 }
169 
170 // Scale is passed through to the pose Shape object.
172 {
173  //pose_->setScale(Ogre::Vector3(scale, scale, scale));
174  mean_->setScale(Ogre::Vector3(scale, scale, scale));
175  covariance_->setLineWidth(scale);
176  scale_ = scale;
177 }
178 
179 // Color is passed through to the pose Shape object.
180 void ObjectDetectionVisual::setColor(Ogre::ColourValue color)
181 {
182  pose_->setColor(color);
183  mean_->setColor(color);
184  covariance_->setColor(color);
185  detection_id_->setColor(color);
186  color_ = color;
187 }
188 
189 void ObjectDetectionVisual::setVisiblities(bool render_covariance, bool render_id, bool render_sensor_type, bool render_pose)
190 {
191  covariance_->setVisible(render_covariance);
192  detection_id_->setVisible(render_id);
193  pose_->getSceneNode()->setVisible(render_pose, true);
194 }
195 
197 {
198 
199 }
200 
201 } // end namespace marker_rviz
virtual void setColor(Ogre::ColourValue color)
virtual void setMessage(const tuw_object_msgs::ObjectWithCovariance::ConstPtr &msg)
void setFramePosition(const Ogre::Vector3 &position)
#define ROS_WARN(...)
void setVisiblities(bool render_covariance, bool render_id, bool render_sensor_type, bool render_pose)
boost::shared_ptr< rviz::Shape > mean_
boost::shared_ptr< CovarianceVisual > covariance_
boost::shared_ptr< rviz::Arrow > pose_
void setFrameOrientation(const Ogre::Quaternion &orientation)
Styles
Visualization style for an object.
Definition: common.h:40
void setTransform(const Ogre::Vector3 &position, const Ogre::Quaternion &orientation)
ObjectDetectionVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
boost::shared_ptr< TextVisual > detection_id_


tuw_object_rviz
Author(s): Florian Beck
autogenerated on Mon Jun 10 2019 15:40:17