24 #ifndef GAZEBO_ROS_VIDEO_H 25 #define GAZEBO_ROS_VIDEO_H 27 #include <boost/thread/mutex.hpp> 30 #include <opencv2/opencv.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);
67 void processImage(
const sensor_msgs::ImageConstPtr &
msg);
71 virtual void UpdateChild();
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
VideoVisual(const std::string &name, rendering::VisualPtr parent, int height, int width)
std::string robot_namespace_
rendering::VisualPtr model_
bool new_image_available_
ros::CallbackQueue queue_
event::ConnectionPtr update_connection_
void render(const cv::Mat &image)
ros::Subscriber camera_subscriber_
cv_bridge::CvImagePtr image_
boost::thread callback_queue_thread_
Ogre::TexturePtr texture_
boost::shared_ptr< VideoVisual > video_visual_