gazebo_ros_multicamera.h
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GAZEBO_ROS_MULTICAMERA_HH
19 #define GAZEBO_ROS_MULTICAMERA_HH
20 
21 #include <string>
22 #include <vector>
23 
24 // library for processing camera data for gazebo / ros conversions
27 
28 namespace gazebo
29 {
31  {
34  public: GazeboRosMultiCamera();
35 
37  public: ~GazeboRosMultiCamera();
38 
41  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
42 
43  std::vector<GazeboRosCameraUtils*> utils;
44 
45  protected: void OnNewFrame(const unsigned char *_image,
46  GazeboRosCameraUtils* util);
49  protected: virtual void OnNewFrameLeft(const unsigned char *_image,
50  unsigned int _width, unsigned int _height,
51  unsigned int _depth, const std::string &_format);
52  protected: virtual void OnNewFrameRight(const unsigned char *_image,
53  unsigned int _width, unsigned int _height,
54  unsigned int _depth, const std::string &_format);
55 
62  };
63 }
64 #endif
65 
gazebo::GazeboRosMultiCamera::OnNewFrame
void OnNewFrame(const unsigned char *_image, GazeboRosCameraUtils *util)
Definition: gazebo_ros_multicamera.cpp:102
boost::shared_ptr< int >
gazebo
gazebo::GazeboRosMultiCamera::image_connect_count_lock_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
Definition: gazebo_ros_multicamera.h:60
gazebo::GazeboRosMultiCamera::image_connect_count_
boost::shared_ptr< int > image_connect_count_
Definition: gazebo_ros_multicamera.h:59
gazebo::GazeboRosMultiCamera
Definition: gazebo_ros_multicamera.h:30
MultiCameraPlugin.h
gazebo::GazeboRosMultiCamera::utils
std::vector< GazeboRosCameraUtils * > utils
Definition: gazebo_ros_multicamera.h:43
gazebo::GazeboRosCameraUtils
Definition: gazebo_ros_camera_utils.h:56
gazebo::GazeboRosMultiCamera::OnNewFrameLeft
virtual void OnNewFrameLeft(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller FIXME: switch to function vectors.
Definition: gazebo_ros_multicamera.cpp:136
gazebo::GazeboRosMultiCamera::was_active_
boost::shared_ptr< bool > was_active_
Definition: gazebo_ros_multicamera.h:61
gazebo::GazeboRosMultiCamera::~GazeboRosMultiCamera
~GazeboRosMultiCamera()
Destructor.
Definition: gazebo_ros_multicamera.cpp:48
gazebo_ros_camera_utils.h
gazebo::GazeboRosMultiCamera::OnNewFrameRight
virtual void OnNewFrameRight(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Definition: gazebo_ros_multicamera.cpp:145
gazebo::GazeboRosMultiCamera::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_multicamera.cpp:52
gazebo::MultiCameraPlugin
Definition: MultiCameraPlugin.h:30
gazebo::GazeboRosMultiCamera::GazeboRosMultiCamera
GazeboRosMultiCamera()
Constructor.
Definition: gazebo_ros_multicamera.cpp:42


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55