39 #include <OGRE/OgreMaterialManager.h> 40 #include <OGRE/OgreMaterial.h> 41 #include <OGRE/OgreBlendMode.h> 43 #include <OGRE/OgreHardwarePixelBuffer.h> 48 Ogre::SceneManager* manager,
49 Ogre::SceneNode* node,
53 const std::string& name,
54 const Ogre::ColourValue& color,
60 manual_ = manager->createManualObject();
63 Ogre::RenderOperation::OT_TRIANGLE_STRIP);
64 manual_->position(O.x, O.y, O.z);
74 manual_->position(A.x, A.y, A.z);
84 manual_->position(B.x, B.y, B.z);
112 "far clip distance from the origin of camera info",
117 "show edges of the region of the camera info",
122 "show polygons of the region of the camera info",
125 "not show side polygons",
127 "do not show polygons of the region of the camera info",
132 "use image as texture",
136 ros::message_traits::datatype<sensor_msgs::Image>(),
137 "sensor_msgs::Image topic to subscribe to.",
142 "transport hint for image subscription",
148 QColor(85, 255, 255),
149 "color of CameraInfo",
153 QColor(125, 125, 125),
154 "edge color of CameraInfo",
159 "alpha blending value",
202 const sensor_msgs::CameraInfo::ConstPtr& msg)
208 Ogre::Vector3 position;
209 Ogre::Quaternion quaternion;
214 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'",
215 qPrintable(
getName() ), msg->header.frame_id.c_str(),
236 const sensor_msgs::CameraInfo::ConstPtr& msg)
240 msg->header.frame_id ==
camera_info_->header.frame_id &&
243 msg->distortion_model ==
camera_info_->distortion_model;
245 for (
size_t i = 0; i < msg->P.size(); i++) {
262 const cv::Point3d& point)
272 const cv::Point3d& O,
const cv::Point3d&
A,
const cv::Point3d& B, std::string name,
bool use_color,
bool upper_triangle)
291 static uint32_t
count = 0;
293 ss <<
"CameraInfoDisplayPolygonBottom" << count++;
295 = Ogre::MaterialManager::getSingleton().create(
297 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
300 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
301 Ogre::TEX_TYPE_2D, width, height, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
308 material_bottom_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
313 material_bottom_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
315 material_bottom_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
323 static uint32_t
count = 0;
325 ss <<
"CameraInfoDisplayPolygon" << count++;
327 = Ogre::MaterialManager::getSingleton().create(
329 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
330 texture_ = Ogre::TextureManager::getSingleton().createManual(
332 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
333 Ogre::TEX_TYPE_2D, 1, 1, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
334 material_->getTechnique(0)->getPass(0)->setColourWriteEnabled(
true);
337 material_->getTechnique(0)->getPass(0)->setAmbient(color);
339 material_->getTechnique(0)->setLightingEnabled(
true);
340 material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
341 material_->getTechnique(0)->getPass(0)->setLightingEnabled(
false);
342 material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(
false);
343 material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(
true);
345 material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
346 material_->getTechnique(0)->getPass(0)->createTextureUnitState(
texture_->getName());
347 material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
367 bottom_texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
368 const Ogre::PixelBox& pixelBox
370 Ogre::uint8* pDest =
static_cast<Ogre::uint8*
> (pixelBox.data);
380 ROS_DEBUG(
"image_.cols: %d",
image_.cols);
382 std::vector<cv::Mat> splitted;
383 cv::split(
image_, splitted);
385 std::swap(splitted[0], splitted[2]);
387 splitted.push_back(alpha);
388 cv::Mat boxMat(
image_.rows,
image_.cols, CV_8UC4, pDest);
389 cv::merge(splitted, boxMat);
395 Hud.setPixel(i, j,
color_.rgba());
404 const sensor_msgs::Image::ConstPtr& msg)
425 ROS_ERROR(
"cv_bridge exception: %s", e.what());
430 const sensor_msgs::CameraInfo::ConstPtr& msg)
438 if (!model_success_p) {
440 ROS_ERROR(
"failed to create camera model");
444 if (model.
fx() == 0.0 || model.
fy() == 0.0) {
457 edges_->setLineWidth(0.01);
460 cv::Point2d a(0, 0),
b(msg->width, 0),
461 c(msg->width, msg->height),
d(0, msg->height);
473 cv::Point3d O(0, 0, 0);
486 material_->getTechnique(0)->getPass(0)->setAmbient(color);
488 texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
489 const Ogre::PixelBox& pixelBox
490 =
texture_->getBuffer()->getCurrentLock();
491 Ogre::uint8* pDest =
static_cast<Ogre::uint8*
> (pixelBox.data);
493 QImage Hud(pDest, 1, 1, QImage::Format_ARGB32 );
494 Hud.setPixel(0, 0,
color_.rgba());
513 edges_->setMaxPointsPerLine(2);
virtual QColor getColor() const
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
bool not_show_side_polygons_
Ogre::TexturePtr bottom_texture_
const cv::Matx33d & intrinsicMatrix() const
virtual void addPointToEdge(const cv::Point3d &point)
virtual void onInitialize()
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::RosTopicProperty * image_topic_property_
DisplayContext * context_
rviz::ColorProperty * color_property_
rviz::BoolProperty * use_image_property_
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
image_transport::Subscriber image_sub_
virtual float getFloat() const
sensor_msgs::CameraInfo::ConstPtr camera_info_
void updateShowPolygons()
Ogre::MaterialPtr material_
rviz::FloatProperty * alpha_property_
Ogre::SceneNode * scene_node_
std::string getStdString()
virtual ~TrianglePolygon()
virtual ~CameraInfoDisplay()
virtual void createTextureForBottom(int width, int height)
Ogre::ColourValue qtToOgre(const QColor &c)
virtual bool getBool() const
image_transport::TransportHints getTransportHints()
Ogre::ManualObject * manual_
virtual void createCameraInfoShapes(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Ogre::MaterialPtr material_bottom_
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
rviz::BoolProperty * show_edges_property_
virtual void onInitialize()
rviz::ColorProperty * edge_color_property_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void update(float wall_dt, float ros_dt)
virtual FrameManager * getFrameManager() const =0
virtual void addPolygon(const cv::Point3d &O, const cv::Point3d &A, const cv::Point3d &B, std::string name, bool use_color, bool upper_triangle)
double far_clip_distance_
virtual void drawImageTexture()
virtual bool isSameCameraInfo(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Ogre::SceneManager * scene_manager_
virtual Ogre::SceneManager * getSceneManager() const =0
ImageTransportHintsProperty * image_transport_hints_property_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
std::vector< TrianglePolygon::Ptr > polygons_
TrianglePolygon(Ogre::SceneManager *manager, Ogre::SceneNode *node, const cv::Point3d &O, const cv::Point3d &A, const cv::Point3d &B, const std::string &name, const Ogre::ColourValue &color, bool use_color, bool upper_triangle)
rviz::FloatProperty * far_clip_distance_property_
#define ROS_ERROR_STREAM(args)
Ogre::TexturePtr texture_
void updateFarClipDistance()
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual void subscribeImage(std::string topic)
virtual QString getName() const
virtual void processMessage(const sensor_msgs::CameraInfo::ConstPtr &msg)
virtual void prepareMaterial()
rviz::BoolProperty * not_show_side_polygons_property_
rviz::BoolProperty * show_polygons_property_
void updateNotShowSidePolygons()