18 #include <boost/algorithm/string/replace.hpp> 22 #include <gazebo/transport/Node.hh> 23 #include <gazebo/transport/Publisher.hh> 44 std::string globalTopicName =
"~/";
45 globalTopicName += this->
parentSensor->Name() +
"/" + this->GetHandle() +
"/" + topicName;
46 boost::replace_all(globalTopicName,
"::",
"/");
48 return globalTopicName;
58 this->
node = transport::NodePtr(
new transport::Node());
62 if (_sdf->HasElement(
"belt_start_velocity"))
64 this->
beltVelocity = _sdf->Get<
double>(
"belt_start_velocity");
69 gzdbg <<
"Using belt start velocity of: " << this->
beltVelocity <<
" m/s\n";
71 std::string controlCommandTopic;
72 if (_sdf->HasElement(
"control_command_topic"))
74 controlCommandTopic = _sdf->Get<std::string>(
"control_command_topic");
77 controlCommandTopic = this->
Topic(
"control_command");
82 if (_sdf->HasElement(
"velocity_axis"))
84 this->
velocityAxis = _sdf->Get<ignition::math::Vector3d>(
"velocity_axis");
88 gzerr <<
"'velocity_axis' tag not found\n";
98 gzdbg <<
"Number of links ontop of belt: " << this->
contactingLinks.size() <<
"\n";
101 std::lock_guard<std::mutex> lock(this->
mutex);
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);
114 linkPtr->SetLinearVel(velocity_worldFrame);
122 double requestedVelocity = std::stod(_msg->str_id());
123 gzdbg <<
"Received control command of: " << requestedVelocity <<
"\n";
130 std::lock_guard<std::mutex> lock(this->
mutex);
131 gzdbg <<
"Setting velocity to: " << velocity <<
"\n";
double beltVelocity
Belt velocity (m/s)
transport::SubscriberPtr controlCommandSub
Subscriber for the control commands.
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.
std::mutex mutex
Mutex to protect the belt velocity.
ignition::math::Vector3d velocityAxis
Axis for belt velocity in local frame (+Y by default)
virtual ~ConveyorBeltPlugin()
Destructor.
void ActOnContactingLinks(double velocity)
Act on links that are ontop of the belt.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)
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.