ROSLogicalCameraPlugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 _ROS_LOGICAL_CAMERA_PLUGIN_HH_
19 #define _ROS_LOGICAL_CAMERA_PLUGIN_HH_
20 
21 #include <sdf/sdf.hh>
22 
23 #include "gazebo/common/Plugin.hh"
24 #include "gazebo/common/UpdateInfo.hh"
25 #include "gazebo/msgs/logical_camera_image.pb.h"
26 #include "gazebo/physics/PhysicsTypes.hh"
27 #include "gazebo/transport/Node.hh"
28 #include "gazebo/transport/Subscriber.hh"
29 #include "gazebo/transport/TransportTypes.hh"
30 
31 // ROS
32 #include <ros/ros.h>
33 
34 namespace gazebo
35 {
37  class ROSLogicalCameraPlugin : public ModelPlugin
38  {
40  public: ROSLogicalCameraPlugin();
41 
43  public: virtual ~ROSLogicalCameraPlugin();
44 
46  protected: physics::ModelPtr model;
47 
49  protected: physics::LinkPtr cameraLink;
50 
52  protected: sensors::SensorPtr sensor;
53 
57  public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
58 
60  protected: void FindLogicalCamera();
61 
64  public: void OnImage(ConstLogicalCameraImagePtr &_msg);
65 
67  protected: transport::NodePtr node;
68 
70  protected: transport::SubscriberPtr imageSub;
71 
73  protected: std::string robotNamespace;
74 
76  protected: ros::NodeHandle *rosnode;
77 
80  };
81 }
82 #endif
sensors::SensorPtr sensor
The logical camera sensor.
virtual ~ROSLogicalCameraPlugin()
Destructor.
ROS publisher for the logical camera.
void OnImage(ConstLogicalCameraImagePtr &_msg)
Callback for when logical camera images are received.
physics::LinkPtr cameraLink
Link that holds the logical camera.
transport::SubscriberPtr imageSub
Subscription to logical camera image messages from gazebo.
ros::Publisher imagePub
ROS publisher for the logical camera image.
transport::NodePtr node
Node for communication with gazebo.
physics::ModelPtr model
Model that contains the logical camera.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
void FindLogicalCamera()
Searches the model links for a logical camera sensor.
ros::NodeHandle * rosnode
ros node handle
std::string robotNamespace
for setting ROS name space


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:12