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 #ifdef ENABLE_PROFILER
20 #include <ignition/common/Profiler.hh>
21 #endif
22 #include <sdf/sdf.hh>
23 
25 
26 namespace gazebo
27 {
28 
29 // Register this plugin with the simulator
30 GZ_REGISTER_MODEL_PLUGIN(GazeboRosHarness)
31 
34 {
35 }
36 
39 {
40  // Custom Callback Queue
41  this->queue_.clear();
42  this->queue_.disable();
43 
44  this->rosnode_->shutdown();
45  delete this->rosnode_;
46 }
47 
49 // Load the controller
50 void GazeboRosHarness::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
51 {
52  // Load the plugin
53  HarnessPlugin::Load(_parent, _sdf);
54 
55  this->robotNamespace_ = "";
56  if (_sdf->HasElement("robotNamespace"))
57  this->robotNamespace_ = _sdf->Get<std::string>("robotNamespace") + "/";
58 
59  // Init ROS
60  if (!ros::isInitialized())
61  {
62  ROS_FATAL_STREAM_NAMED("harness", "Not loading plugin since ROS hasn't been "
63  << "properly initialized. Try starting gazebo with ros plugin:\n"
64  << " gazebo -s libgazebo_ros_api_plugin.so\n");
65  return;
66  }
67 
68  this->rosnode_ = new ros::NodeHandle(this->robotNamespace_);
69 
70  ros::SubscribeOptions so = ros::SubscribeOptions::create<std_msgs::Float32>(
71  "/" + _parent->GetName() + "/harness/velocity", 1,
72  boost::bind(&GazeboRosHarness::OnVelocity, this, _1),
73  ros::VoidPtr(), &this->queue_);
74  this->velocitySub_ = this->rosnode_->subscribe(so);
75 
76  so = ros::SubscribeOptions::create<std_msgs::Bool>(
77  "/" + _parent->GetName() + "/harness/detach", 1,
78  boost::bind(&GazeboRosHarness::OnDetach, this, _1),
79  ros::VoidPtr(), &this->queue_);
80  this->detachSub_ = this->rosnode_->subscribe(so);
81 
82  // Custom Callback Queue
83  this->callbackQueueThread_ =
84  boost::thread(boost::bind(&GazeboRosHarness::QueueThread, this));
85 }
86 
88 void GazeboRosHarness::OnVelocity(const std_msgs::Float32::ConstPtr &msg)
89 {
90 #ifdef ENABLE_PROFILER
91  IGN_PROFILE("GazeboRosHarness::OnVelocity");
92  IGN_PROFILE_BEGIN("process ROS message");
93 #endif
94  // Set the target winch velocity
95  this->SetWinchVelocity(msg->data);
96 #ifdef ENABLE_PROFILER
97  IGN_PROFILE_END();
98 #endif
99 }
100 
102 void GazeboRosHarness::OnDetach(const std_msgs::Bool::ConstPtr &msg)
103 {
104  // Detach if true
105  if (msg->data)
106  this->Detach();
107 }
108 
111 {
112  static const double timeout = 0.01;
113 
114  while (this->rosnode_->ok())
115  {
116  this->queue_.callAvailable(ros::WallDuration(timeout));
117  }
118 }
119 }
gazebo::GazeboRosHarness::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_harness.h:76
msg
msg
boost::shared_ptr< void >
gazebo
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosHarness::OnVelocity
virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg)
Receive winch velocity control messages.
Definition: gazebo_ros_harness.cpp:88
gazebo::GazeboRosHarness::detachSub_
ros::Subscriber detachSub_
Subscriber to detach control messages.
Definition: gazebo_ros_harness.h:72
gazebo::GazeboRosHarness::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_harness.h:66
gazebo::GazeboRosHarness::callbackQueueThread_
boost::thread callbackQueueThread_
Definition: gazebo_ros_harness.h:77
gazebo::GazeboRosHarness::Load
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_harness.cpp:50
gazebo::GazeboRosHarness::robotNamespace_
std::string robotNamespace_
for setting ROS name space
Definition: gazebo_ros_harness.h:75
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo_ros_harness.h
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosHarness::~GazeboRosHarness
virtual ~GazeboRosHarness()
Destructor.
Definition: gazebo_ros_harness.cpp:38
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
gazebo::GazeboRosHarness::velocitySub_
ros::Subscriber velocitySub_
Subscriber to velocity control messages.
Definition: gazebo_ros_harness.h:69
ros::NodeHandle::ok
bool ok() const
ros::SubscribeOptions
gazebo::GazeboRosHarness::OnDetach
virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg)
Receive detach messages.
Definition: gazebo_ros_harness.cpp:102
ros::WallDuration
gazebo::GazeboRosHarness::GazeboRosHarness
GazeboRosHarness()
Constructor.
Definition: gazebo_ros_harness.cpp:33
ros::NodeHandle::shutdown
void shutdown()
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosHarness::QueueThread
void QueueThread()
Custom callback queue thread.
Definition: gazebo_ros_harness.cpp:110
ros::NodeHandle


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28