Go to the documentation of this file.
37 #ifndef JSK_RVIZ_PLUGINS_CAMERA_INFO_DISPLAY_H_
38 #define JSK_RVIZ_PLUGINS_CAMERA_INFO_DISPLAY_H_
49 #include <OGRE/OgreSceneNode.h>
51 #include <sensor_msgs/Image.h>
52 #include <OGRE/OgreManualObject.h>
53 #include <OGRE/OgreSceneManager.h>
54 #include <OGRE/OgreTextureManager.h>
55 #include <OGRE/OgreTexture.h>
68 #if ROS_VERSION_MINIMUM(1,12,0)
69 typedef std::shared_ptr<TrianglePolygon>
Ptr;
74 Ogre::SceneNode* node,
78 const std::string& name,
79 const Ogre::ColourValue& color,
90 class CameraInfoDisplay:
95 #if ROS_VERSION_MINIMUM(1,12,0)
96 typedef std::shared_ptr<rviz::Shape>
ShapePtr;
110 virtual void reset();
111 virtual void processMessage(
const sensor_msgs::CameraInfo::ConstPtr& msg);
115 virtual void update(
float wall_dt,
float ros_dt);
117 const sensor_msgs::CameraInfo::ConstPtr& camera_info);
119 const sensor_msgs::CameraInfo::ConstPtr& camera_info);
121 const cv::Point3d& point);
123 const cv::Point3d& O,
const cv::Point3d&
A,
const cv::Point3d& B, std::string name,
124 bool use_color,
bool upper_triangle);
127 virtual void imageCallback(
const sensor_msgs::Image::ConstPtr& msg);
133 std::vector<TrianglePolygon::Ptr>
polygons_;
rviz::BoolProperty * show_edges_property_
Ogre::ManualObject * manual_
ImageTransportHintsProperty * image_transport_hints_property_
virtual void subscribeImage(std::string topic)
boost::shared_ptr< rviz::Shape > ShapePtr
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)
virtual void prepareMaterial()
void updateNotShowSidePolygons()
sensor_msgs::CameraInfo::ConstPtr camera_info_
void updateShowPolygons()
void updateFarClipDistance()
rviz::BoolProperty * use_image_property_
virtual ~CameraInfoDisplay()
image_transport::Subscriber image_sub_
std::vector< TrianglePolygon::Ptr > polygons_
virtual void createCameraInfoShapes(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
virtual void addPointToEdge(const cv::Point3d &point)
virtual void drawImageTexture()
virtual void addPolygon(const cv::Point3d &O, const cv::Point3d &A, const cv::Point3d &B, std::string name, bool use_color, bool upper_triangle)
virtual bool isSameCameraInfo(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
rviz::BoolProperty * show_polygons_property_
Ogre::MaterialPtr material_bottom_
Ogre::TexturePtr texture_
virtual ~TrianglePolygon()
virtual void update(float wall_dt, float ros_dt)
double far_clip_distance_
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
rviz::RosTopicProperty * image_topic_property_
rviz::ColorProperty * color_property_
bool not_show_side_polygons_
virtual void createTextureForBottom(int width, int height)
Ogre::SceneManager * manager_
Ogre::TexturePtr bottom_texture_
rviz::FloatProperty * far_clip_distance_property_
rviz::ColorProperty * edge_color_property_
Ogre::MaterialPtr material_
rviz::FloatProperty * alpha_property_
rviz::BoolProperty * not_show_side_polygons_property_
boost::shared_ptr< rviz::BillboardLine > BillboardLinePtr
boost::shared_ptr< TrianglePolygon > Ptr
virtual void processMessage(const sensor_msgs::CameraInfo::ConstPtr &msg)
virtual void onInitialize()
jsk_rviz_plugins
Author(s): Kei Okada
, Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Fri Aug 2 2024 08:50:14