39 #include <OGRE/OgreMaterialManager.h>
40 #include <OGRE/OgreMaterial.h>
41 #include <OGRE/OgreBlendMode.h>
43 #include <OGRE/OgreHardwarePixelBuffer.h>
51 Ogre::SceneManager* manager,
52 Ogre::SceneNode* node,
56 const std::string& name,
57 const Ogre::ColourValue& color,
63 manual_ = manager->createManualObject();
66 Ogre::RenderOperation::OT_TRIANGLE_STRIP);
67 manual_->position(O.x, O.y, O.z);
87 manual_->position(B.x, B.y, B.z);
115 "far clip distance from the origin of camera info",
116 this, SLOT(updateFarClipDistance()));
120 "show edges of the region of the camera info",
121 this, SLOT(updateShowEdges()));
125 "show polygons of the region of the camera info",
126 this, SLOT(updateShowPolygons()));
128 "not show side polygons",
130 "do not show polygons of the region of the camera info",
131 this, SLOT(updateNotShowSidePolygons()));
135 "use image as texture",
136 this, SLOT(updateUseImage()));
139 ros::message_traits::datatype<sensor_msgs::Image>(),
140 "sensor_msgs::Image topic to subscribe to.",
141 this, SLOT( updateImageTopic() ));
142 image_topic_property_->hide();
145 "transport hint for image subscription",
146 this, SLOT( updateImageTopic() ));
147 image_transport_hints_property_->hide();
151 QColor(85, 255, 255),
152 "color of CameraInfo",
153 this, SLOT(updateColor()));
156 QColor(125, 125, 125),
157 "edge color of CameraInfo",
158 this, SLOT(updateEdgeColor()));
162 "alpha blending value",
163 this, SLOT(updateAlpha()));
205 const sensor_msgs::CameraInfo::ConstPtr& msg)
211 Ogre::Vector3 position;
212 Ogre::Quaternion quaternion;
214 if (frame_id[0] ==
'/') {
221 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'",
222 qPrintable(
getName() ),
msg->header.frame_id.c_str(),
243 const sensor_msgs::CameraInfo::ConstPtr& msg)
256 for (
size_t i = 0; i <
msg->P.size(); i++) {
273 const cv::Point3d& point)
283 const cv::Point3d& O,
const cv::Point3d&
A,
const cv::Point3d& B, std::string name,
bool use_color,
bool upper_triangle)
302 static uint32_t
count = 0;
304 ss <<
"CameraInfoDisplayPolygonBottom" <<
count++;
306 = Ogre::MaterialManager::getSingleton().create(
308 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
311 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
312 Ogre::TEX_TYPE_2D, width, height, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
319 material_bottom_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
324 material_bottom_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
326 material_bottom_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
334 static uint32_t
count = 0;
336 ss <<
"CameraInfoDisplayPolygon" <<
count++;
338 = Ogre::MaterialManager::getSingleton().create(
340 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
341 texture_ = Ogre::TextureManager::getSingleton().createManual(
343 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
344 Ogre::TEX_TYPE_2D, 1, 1, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
345 material_->getTechnique(0)->getPass(0)->setColourWriteEnabled(
true);
348 material_->getTechnique(0)->getPass(0)->setAmbient(color);
350 material_->getTechnique(0)->setLightingEnabled(
true);
351 material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
352 material_->getTechnique(0)->getPass(0)->setLightingEnabled(
false);
353 material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(
false);
354 material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(
true);
356 material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
357 material_->getTechnique(0)->getPass(0)->createTextureUnitState(
texture_->getName());
358 material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
378 bottom_texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
379 const Ogre::PixelBox& pixelBox
381 Ogre::uint8* pDest =
static_cast<Ogre::uint8*
> (pixelBox.data);
393 std::vector<cv::Mat> splitted;
394 cv::split(
image_, splitted);
396 std::swap(splitted[0], splitted[2]);
398 splitted.push_back(
alpha);
399 cv::Mat boxMat(
image_.rows,
image_.cols, CV_8UC4, pDest);
400 cv::merge(splitted, boxMat);
406 Hud.setPixel(i, j,
color_.rgba());
415 const sensor_msgs::Image::ConstPtr& msg)
425 cv::Mat im = cv_ptr->image.clone();
426 if (
msg->encoding == enc::BGRA8) {
427 cv::cvtColor(im, im, cv::COLOR_BGRA2RGB);
428 }
else if (
msg->encoding == enc::BGRA16) {
429 im.convertTo(im, CV_8U, 1 / 256.0);
430 cv::cvtColor(im, im, cv::COLOR_BGRA2RGB);
431 }
else if (
msg->encoding == enc::BGR8) {
432 cv::cvtColor(im, im, cv::COLOR_BGR2RGB);
433 }
else if (
msg->encoding == enc::BGR16) {
434 im.convertTo(im, CV_8U, 1 / 256.0);
435 cv::cvtColor(im, im, cv::COLOR_BGR2RGB);
436 }
else if (
msg->encoding == enc::RGBA8) {
437 cv::cvtColor(im, im, cv::COLOR_RGBA2RGB);
438 }
else if (
msg->encoding == enc::RGBA16) {
439 im.convertTo(im, CV_8U, 1 / 256.0);
440 cv::cvtColor(im, im, cv::COLOR_RGBA2RGB);
441 }
else if (
msg->encoding == enc::RGB8) {
443 }
else if (
msg->encoding == enc::RGB16) {
444 im.convertTo(im, CV_8U, 1 / 256.0);
445 }
else if (
msg->encoding == enc::MONO8) {
446 cv::cvtColor(im, im, cv::COLOR_GRAY2RGB);
447 }
else if (
msg->encoding == enc::MONO16) {
448 im.convertTo(im, CV_8U, 1 / 256.0);
449 cv::cvtColor(im, im, cv::COLOR_GRAY2RGB);
451 ROS_ERROR(
"[CameraInfoDisplay] Not supported image encodings %s.",
msg->encoding.c_str());
468 image_ = cv::Mat(im, roi).clone();
469 }
else if (im.cols == roi_width && im.rows == roi_height) {
472 ROS_ERROR(
"[CameraInfoDisplay] Invalid image size (w, h) = (%d, %d), expected (w, h) = (%d, %d) or (%d, %d) (ROI size)",
475 roi_width, roi_height);
492 ROS_ERROR(
"cv_bridge exception: %s", e.what());
497 const sensor_msgs::CameraInfo::ConstPtr& msg)
505 if (!model_success_p) {
507 ROS_ERROR(
"failed to create camera model");
511 if (model.
fx() == 0.0 || model.
fy() == 0.0) {
524 edges_->setLineWidth(0.01);
529 if (
msg->binning_y > 0) {
532 if (
msg->binning_x > 0) {
536 cv::Point2d a(0, 0),
b(width, 0),
537 c(width, height),
d(0, height);
549 cv::Point3d O(0, 0, 0);
562 material_->getTechnique(0)->getPass(0)->setAmbient(color);
564 texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
565 const Ogre::PixelBox& pixelBox
566 =
texture_->getBuffer()->getCurrentLock();
567 Ogre::uint8* pDest =
static_cast<Ogre::uint8*
> (pixelBox.data);
569 QImage Hud(pDest, 1, 1, QImage::Format_ARGB32 );
570 Hud.setPixel(0, 0,
color_.rgba());
589 edges_->setMaxPointsPerLine(2);