mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
"using" directives are no longer used in global namespaces (#219)
This commit is contained in:
committed by
Peter Johnson
parent
78f0b1562c
commit
ba8761e39e
@@ -11,7 +11,7 @@
|
||||
|
||||
GZ_REGISTER_MODEL_PLUGIN(Encoder)
|
||||
|
||||
void Encoder::Load(physics::ModelPtr model, sdf::ElementPtr sdf) {
|
||||
void Encoder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
|
||||
this->model = model;
|
||||
|
||||
// Parse SDF properties
|
||||
@@ -38,20 +38,20 @@ void Encoder::Load(physics::ModelPtr model, sdf::ElementPtr sdf) {
|
||||
std::string scoped_name =
|
||||
model->GetWorld()->GetName() + "::" + model->GetScopedName();
|
||||
boost::replace_all(scoped_name, "::", "/");
|
||||
node = transport::NodePtr(new transport::Node());
|
||||
node = gazebo::transport::NodePtr(new gazebo::transport::Node());
|
||||
node->Init(scoped_name);
|
||||
command_sub = node->Subscribe(topic + "/control", &Encoder::Callback, this);
|
||||
pos_pub = node->Advertise<msgs::Float64>(topic + "/position");
|
||||
vel_pub = node->Advertise<msgs::Float64>(topic + "/velocity");
|
||||
pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
|
||||
vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
|
||||
|
||||
// Connect to the world update event.
|
||||
// This will trigger the Update function every Gazebo iteration
|
||||
updateConn = event::Events::ConnectWorldUpdateBegin(
|
||||
updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
|
||||
boost::bind(&Encoder::Update, this, _1));
|
||||
}
|
||||
|
||||
void Encoder::Update(const common::UpdateInfo& info) {
|
||||
msgs::Float64 pos_msg, vel_msg;
|
||||
void Encoder::Update(const gazebo::common::UpdateInfo& info) {
|
||||
gazebo::msgs::Float64 pos_msg, vel_msg;
|
||||
if (stopped) {
|
||||
pos_msg.set_data(stop_value);
|
||||
pos_pub->Publish(pos_msg);
|
||||
@@ -65,7 +65,7 @@ void Encoder::Update(const common::UpdateInfo& info) {
|
||||
}
|
||||
}
|
||||
|
||||
void Encoder::Callback(const msgs::ConstStringPtr& msg) {
|
||||
void Encoder::Callback(const gazebo::msgs::ConstStringPtr& msg) {
|
||||
std::string command = msg->data();
|
||||
if (command == "reset") {
|
||||
zero = GetAngle();
|
||||
|
||||
@@ -15,8 +15,6 @@
|
||||
|
||||
#include "simulation/gz_msgs/msgs.h"
|
||||
|
||||
using namespace gazebo;
|
||||
|
||||
/**
|
||||
* \brief Plugin for reading the speed and relative angle of a joint.
|
||||
*
|
||||
@@ -45,13 +43,13 @@ using namespace gazebo;
|
||||
* (gazebo.msgs.String)
|
||||
* - `units`: Optional. Defaults to radians.
|
||||
*/
|
||||
class Encoder : public ModelPlugin {
|
||||
class Encoder : public gazebo::ModelPlugin {
|
||||
public:
|
||||
/// \brief Load the encoder and configures it according to the sdf.
|
||||
void Load(physics::ModelPtr model, sdf::ElementPtr sdf);
|
||||
void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
|
||||
|
||||
/// \brief Sends out the encoder reading each timestep.
|
||||
void Update(const common::UpdateInfo& info);
|
||||
void Update(const gazebo::common::UpdateInfo& info);
|
||||
|
||||
private:
|
||||
/// \brief Root topic for subtopics on this topic.
|
||||
@@ -70,10 +68,10 @@ class Encoder : public ModelPlugin {
|
||||
double stop_value;
|
||||
|
||||
/// \brief The joint that this encoder measures
|
||||
physics::JointPtr joint;
|
||||
gazebo::physics::JointPtr joint;
|
||||
|
||||
/// \brief Callback for handling control data
|
||||
void Callback(const msgs::ConstStringPtr& msg);
|
||||
void Callback(const gazebo::msgs::ConstStringPtr& msg);
|
||||
|
||||
/// \brief Gets the current angle, taking into account whether to
|
||||
/// return radians or degrees.
|
||||
@@ -83,10 +81,18 @@ class Encoder : public ModelPlugin {
|
||||
/// return radians/second or degrees/second.
|
||||
double GetVelocity();
|
||||
|
||||
physics::ModelPtr model; ///< \brief The model that this is attached to.
|
||||
event::ConnectionPtr
|
||||
updateConn; ///< \brief Pointer to the world update function.
|
||||
transport::NodePtr node; ///< \brief The node we're advertising on.
|
||||
transport::SubscriberPtr command_sub; ///< \brief Subscriber handle.
|
||||
transport::PublisherPtr pos_pub, vel_pub; ///< \brief Publisher handles.
|
||||
/// \brief The model to which this is attached.
|
||||
gazebo::physics::ModelPtr model;
|
||||
|
||||
/// \brief Pointer to the world update function.
|
||||
gazebo::event::ConnectionPtr updateConn;
|
||||
|
||||
/// \brief The node on which we're advertising.
|
||||
gazebo::transport::NodePtr node;
|
||||
|
||||
/// \brief Subscriber handle.
|
||||
gazebo::transport::SubscriberPtr command_sub;
|
||||
|
||||
/// \brief Publisher handles.
|
||||
gazebo::transport::PublisherPtr pos_pub, vel_pub;
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user