35 #include <OGRE/OgreVector3.h> 36 #include <OGRE/OgreMatrix3.h> 37 #include <OGRE/OgreSceneNode.h> 38 #include <OGRE/OgreSceneManager.h> 73 Ogre::Vector3 position =
74 Ogre::Vector3(msg->object.pose.position.x, msg->object.pose.position.y, msg->object.pose.position.z);
78 Ogre::Vector3 vel = Ogre::Vector3(msg->object.twist.linear.x, msg->object.twist.linear.y, msg->object.twist.linear.z);
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);
83 if(msg->covariance_pose.size() == 9)
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]);
92 Ogre::Matrix3 rotation_mat;
94 C = rotation_mat * C * rotation_mat.Transpose();
98 covariance_->setMeanCovariance(Ogre::Vector3(0, 0, 0), C);
104 ROS_WARN(
"Covariance is not 9x9 won't display");
107 pose_->setPosition(position);
108 pose_->setDirection(vel);
110 pose_->setScale(Ogre::Vector3(0.02 * position.distance(vel), 0.5, 0.5));
123 mean_->setPosition(position);
124 mean_->setScale(Ogre::Vector3(0.1, 0.1, 0.1));
126 detection_id_->setPosition(position - Ogre::Vector3(0, 0, 0.2));
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();
135 for (; (it_ids != msg->object.ids.end()) || (it_conf != msg->object.ids_confidence.end()); it_ids++, it_conf++)
137 std::string conf = (boost::format(
"%.2f") % *it_conf).str();
139 if (it_ids == (msg->object.ids.end() - 1))
141 ids += boost::lexical_cast<std::string>(*it_ids) +
" (" + conf +
")";
145 ids += boost::lexical_cast<std::string>(*it_ids) +
" (" + conf +
")" +
", ";
174 mean_->setScale(Ogre::Vector3(scale, scale, scale));
182 pose_->setColor(color);
183 mean_->setColor(color);
193 pose_->getSceneNode()->setVisible(render_pose,
true);
Ogre::SceneNode * frame_node_
Ogre::SceneManager * scene_manager_
virtual void setColor(Ogre::ColourValue color)
virtual void setMessage(const tuw_object_msgs::ObjectWithCovariance::ConstPtr &msg)
void setFramePosition(const Ogre::Vector3 &position)
void setVisiblities(bool render_covariance, bool render_id, bool render_sensor_type, bool render_pose)
virtual void setScale(float scale)
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.
void setTransform(const Ogre::Vector3 &position, const Ogre::Quaternion &orientation)
virtual ~ObjectDetectionVisual()
ObjectDetectionVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
virtual void setStyle(Styles style)
boost::shared_ptr< TextVisual > detection_id_