ConveyorBeltPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-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 #include <boost/algorithm/string/replace.hpp>
19 #include <string>
20 
21 #include "ConveyorBeltPlugin.hh"
22 #include <gazebo/transport/Node.hh>
23 #include <gazebo/transport/Publisher.hh>
24 
25 using namespace gazebo;
27 
30 {
31 }
32 
35 {
36  event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
37  this->parentSensor.reset();
38  this->world.reset();
39 }
40 
42 std::string ConveyorBeltPlugin::Topic(std::string topicName) const
43 {
44  std::string globalTopicName = "~/";
45  globalTopicName += this->parentSensor->Name() + "/" + this->GetHandle() + "/" + topicName;
46  boost::replace_all(globalTopicName, "::", "/");
47 
48  return globalTopicName;
49 }
50 
52 void ConveyorBeltPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
53 {
54  SideContactPlugin::Load(_model, _sdf);
55 
56  if (!this->node)
57  {
58  this->node = transport::NodePtr(new transport::Node());
59  this->node->Init(this->world->GetName());
60  }
61 
62  if (_sdf->HasElement("belt_start_velocity"))
63  {
64  this->beltVelocity = _sdf->Get<double>("belt_start_velocity");
65  }
66  else {
67  this->beltVelocity = 0.5;
68  }
69  gzdbg << "Using belt start velocity of: " << this->beltVelocity << " m/s\n";
70 
71  std::string controlCommandTopic;
72  if (_sdf->HasElement("control_command_topic"))
73  {
74  controlCommandTopic = _sdf->Get<std::string>("control_command_topic");
75  }
76  else {
77  controlCommandTopic = this->Topic("control_command");
78  }
79  this->controlCommandSub = this->node->Subscribe(controlCommandTopic,
81 
82  if (_sdf->HasElement("velocity_axis"))
83  {
84  this->velocityAxis = _sdf->Get<ignition::math::Vector3d>("velocity_axis");
85  }
86  else
87  {
88  gzerr << "'velocity_axis' tag not found\n";
89  }
90 }
91 
93 void ConveyorBeltPlugin::OnUpdate(const common::UpdateInfo &/*_info*/)
94 {
95  auto prevNumberContactingLinks = this->contactingLinks.size();
97  if (prevNumberContactingLinks != this->contactingLinks.size()) {
98  gzdbg << "Number of links ontop of belt: " << this->contactingLinks.size() << "\n";
99  }
100 
101  std::lock_guard<std::mutex> lock(this->mutex);
102  double velocity = this->beltVelocity;
103  this->ActOnContactingLinks(velocity);
104 }
105 
108 {
109  ignition::math::Vector3d velocity_beltFrame = velocity * this->velocityAxis;
110  auto beltPose = this->parentLink->GetWorldPose().Ign();
111  math::Vector3 velocity_worldFrame = beltPose.Rot().RotateVector(velocity_beltFrame);
112  for (auto linkPtr : this->contactingLinks) {
113  if (linkPtr) {
114  linkPtr->SetLinearVel(velocity_worldFrame);
115  }
116  }
117 }
118 
120 void ConveyorBeltPlugin::OnControlCommand(ConstHeaderPtr& _msg)
121 {
122  double requestedVelocity = std::stod(_msg->str_id());
123  gzdbg << "Received control command of: " << requestedVelocity << "\n";
124  this->SetVelocity(requestedVelocity);
125 }
126 
128 void ConveyorBeltPlugin::SetVelocity(double velocity)
129 {
130  std::lock_guard<std::mutex> lock(this->mutex);
131  gzdbg << "Setting velocity to: " << velocity << "\n";
132  this->beltVelocity = velocity;
133 }
physics::WorldPtr world
Pointer to the world.
double beltVelocity
Belt velocity (m/s)
transport::SubscriberPtr controlCommandSub
Subscriber for the control commands.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the sensor plugin.
transport::NodePtr node
Pointer to this node for publishing/subscribing.
std::string Topic(std::string topicName) const
Generate a scoped topic name from a local one.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the model plugin.
void OnUpdate(const common::UpdateInfo &_info)
Callback that receives the world update event.
A plugin for a model with a contact sensor that only monitors collisions on one of its sides...
std::set< physics::LinkPtr > contactingLinks
Set of pointers to links that have collisions with the parent link&#39;s side.
sensors::ContactSensorPtr parentSensor
Pointer to the contact sensor.
std::mutex mutex
Mutex to protect the belt velocity.
ignition::math::Vector3d velocityAxis
Axis for belt velocity in local frame (+Y by default)
event::ConnectionPtr updateConnection
Pointer to the update event connection.
physics::LinkPtr parentLink
Pointer to the sensor&#39;s parent&#39;s link.
virtual ~ConveyorBeltPlugin()
Destructor.
void ActOnContactingLinks(double velocity)
Act on links that are ontop of the belt.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)
virtual void CalculateContactingLinks()
Determine which links are in contact with the side of the parent link.
void OnControlCommand(ConstHeaderPtr &_msg)
Callback for responding to control commands.
A plugin for a conveyor belt.
void SetVelocity(double velocity)
Set the state of the conveyor belt.


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