gazebo_ros_harness.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 #ifndef GAZEBO_ROS_HARNESS_H
18 #define GAZEBO_ROS_HARNESS_H
19 
20 // Custom Callback Queue
21 #include <ros/callback_queue.h>
22 #include <ros/subscribe_options.h>
23 
24 #include <ros/ros.h>
25 #include <std_msgs/Float32.h>
26 #include <std_msgs/Bool.h>
27 
28 #include <gazebo/plugins/HarnessPlugin.hh>
29 
30 namespace gazebo
31 {
42 class GazeboRosHarness : public HarnessPlugin
43 {
45  public: GazeboRosHarness();
46 
48  public: virtual ~GazeboRosHarness();
49 
51  public: virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
52 
55  private: virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg);
56 
60  private: virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg);
61 
63  private: void QueueThread();
64 
67 
70 
73 
75  private: std::string robotNamespace_;
77  private: boost::thread callbackQueueThread_;
78 };
79 }
80 #endif
msg
ros::Subscriber detachSub_
Subscriber to detach control messages.
ros::NodeHandle * rosnode_
pointer to ros node
std::string robotNamespace_
for setting ROS name space
virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg)
Receive winch velocity control messages.
ros::Subscriber velocitySub_
Subscriber to velocity control messages.
virtual ~GazeboRosHarness()
Destructor.
boost::thread callbackQueueThread_
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics: ...
void QueueThread()
Custom callback queue thread.
ros::CallbackQueue queue_
virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg)
Receive detach messages.


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Apr 6 2021 02:19:39