Go to the documentation of this file.
24 #ifndef GAZEBO_ROS_VIDEO_H
25 #define GAZEBO_ROS_VIDEO_H
27 #include <boost/thread/mutex.hpp>
30 #include <opencv2/core.hpp>
34 #include <sensor_msgs/Image.h>
36 #include <gazebo/common/Events.hh>
37 #include <gazebo/common/Plugin.hh>
38 #include <gazebo/common/Time.hh>
39 #include <gazebo/rendering/rendering.hh>
40 #include <gazebo/transport/TransportTypes.hh>
49 const std::string &name, rendering::VisualPtr parent,
50 int height,
int width);
52 void render(
const cv::Mat& image);
66 void Load(rendering::VisualPtr parent, sdf::ElementPtr sdf);
boost::shared_ptr< VideoVisual > video_visual_
boost::thread callback_queue_thread_
ros::Subscriber camera_subscriber_
event::ConnectionPtr update_connection_
cv_bridge::CvImagePtr image_
std::string robot_namespace_
void render(const cv::Mat &image)
rendering::VisualPtr model_
void processImage(const sensor_msgs::ImageConstPtr &msg)
bool new_image_available_
virtual ~GazeboRosVideo()
ros::CallbackQueue queue_
void Load(rendering::VisualPtr parent, sdf::ElementPtr sdf)
Ogre::TexturePtr texture_
virtual void UpdateChild()
VideoVisual(const std::string &name, rendering::VisualPtr parent, int height, int width)
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55