gazebo_ros_harness.cpp
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 #include <gazebo/physics/World.hh>
18 #include <gazebo/physics/Model.hh>
19 #include <sdf/sdf.hh>
20 
22 
23 namespace gazebo
24 {
25 
26 // Register this plugin with the simulator
27 GZ_REGISTER_MODEL_PLUGIN(GazeboRosHarness)
28 
29 GazeboRosHarness::GazeboRosHarness()
31 {
32 }
33 
36 {
37  // Custom Callback Queue
38  this->queue_.clear();
39  this->queue_.disable();
40 
41  this->rosnode_->shutdown();
42  delete this->rosnode_;
43 }
44 
46 // Load the controller
47 void GazeboRosHarness::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
48 {
49  // Load the plugin
50  HarnessPlugin::Load(_parent, _sdf);
51 
52  this->robotNamespace_ = "";
53  if (_sdf->HasElement("robotNamespace"))
54  this->robotNamespace_ = _sdf->Get<std::string>("robotNamespace") + "/";
55 
56  // Init ROS
57  if (!ros::isInitialized())
58  {
59  ROS_FATAL_STREAM_NAMED("harness", "Not loading plugin since ROS hasn't been "
60  << "properly initialized. Try starting gazebo with ros plugin:\n"
61  << " gazebo -s libgazebo_ros_api_plugin.so\n");
62  return;
63  }
64 
65  this->rosnode_ = new ros::NodeHandle(this->robotNamespace_);
66 
67  ros::SubscribeOptions so = ros::SubscribeOptions::create<std_msgs::Float32>(
68  "/" + _parent->GetName() + "/harness/velocity", 1,
69  boost::bind(&GazeboRosHarness::OnVelocity, this, _1),
70  ros::VoidPtr(), &this->queue_);
71  this->velocitySub_ = this->rosnode_->subscribe(so);
72 
73  so = ros::SubscribeOptions::create<std_msgs::Bool>(
74  "/" + _parent->GetName() + "/harness/detach", 1,
75  boost::bind(&GazeboRosHarness::OnDetach, this, _1),
76  ros::VoidPtr(), &this->queue_);
77  this->detachSub_ = this->rosnode_->subscribe(so);
78 
79  // Custom Callback Queue
80  this->callbackQueueThread_ =
81  boost::thread(boost::bind(&GazeboRosHarness::QueueThread, this));
82 }
83 
85 void GazeboRosHarness::OnVelocity(const std_msgs::Float32::ConstPtr &msg)
86 {
87  // Set the target winch velocity
88  this->SetWinchVelocity(msg->data);
89 }
90 
92 void GazeboRosHarness::OnDetach(const std_msgs::Bool::ConstPtr &msg)
93 {
94  // Detach if true
95  if (msg->data)
96  this->Detach();
97 }
98 
101 {
102  static const double timeout = 0.01;
103 
104  while (this->rosnode_->ok())
105  {
106  this->queue_.callAvailable(ros::WallDuration(timeout));
107  }
108 }
109 }
ros::Subscriber detachSub_
Subscriber to detach control messages.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL bool isInitialized()
ros::NodeHandle * rosnode_
pointer to ros node
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
std::string robotNamespace_
for setting ROS name space
virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg)
Receive winch velocity control messages.
#define ROS_FATAL_STREAM_NAMED(name, args)
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.
bool ok() const
boost::shared_ptr< void > VoidPtr
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 Mar 26 2019 02:31:27