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,
95 #if ROS_VERSION_MINIMUM(1,12,0) 96 typedef std::shared_ptr<rviz::Shape>
ShapePtr;
109 virtual void onInitialize();
110 virtual void reset();
111 virtual void processMessage(
const sensor_msgs::CameraInfo::ConstPtr& msg);
115 virtual void update(
float wall_dt,
float ros_dt);
116 virtual bool isSameCameraInfo(
117 const sensor_msgs::CameraInfo::ConstPtr& camera_info);
118 virtual void createCameraInfoShapes(
119 const sensor_msgs::CameraInfo::ConstPtr& camera_info);
120 virtual void addPointToEdge(
121 const cv::Point3d& point);
122 virtual void addPolygon(
123 const cv::Point3d& O,
const cv::Point3d&
A,
const cv::Point3d& B, std::string name,
124 bool use_color,
bool upper_triangle);
125 virtual void prepareMaterial();
126 virtual void createTextureForBottom(
int width,
int height);
127 virtual void imageCallback(
const sensor_msgs::Image::ConstPtr& msg);
128 virtual void drawImageTexture();
129 virtual void subscribeImage(std::string topic);
170 void updateFarClipDistance();
173 void updateShowEdges();
174 void updateShowPolygons();
175 void updateNotShowSidePolygons();
176 void updateImageTopic();
177 void updateUseImage();
178 void updateEdgeColor();
boost::shared_ptr< rviz::Shape > ShapePtr
bool not_show_side_polygons_
Ogre::TexturePtr bottom_texture_
rviz::RosTopicProperty * image_topic_property_
rviz::ColorProperty * color_property_
rviz::BoolProperty * use_image_property_
image_transport::Subscriber image_sub_
bool update(const T &new_val, T &my_val)
sensor_msgs::CameraInfo::ConstPtr camera_info_
Ogre::MaterialPtr material_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
rviz::FloatProperty * alpha_property_
Ogre::SceneManager * manager_
virtual ~TrianglePolygon()
Ogre::ManualObject * manual_
boost::shared_ptr< TrianglePolygon > Ptr
Ogre::MaterialPtr material_bottom_
rviz::BoolProperty * show_edges_property_
rviz::ColorProperty * edge_color_property_
double far_clip_distance_
ImageTransportHintsProperty * image_transport_hints_property_
boost::shared_ptr< rviz::BillboardLine > BillboardLinePtr
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_
Ogre::TexturePtr texture_
rviz::BoolProperty * not_show_side_polygons_property_
rviz::BoolProperty * show_polygons_property_