- hasPID
- Determines whether the joint has PID in order to be controlled via PID position/effort controller. Takes no value: *<hasPID/>* means that the mimic joint is controlled via PID. Ommit it so that the mimic joint is controlled via setAngle.
+ Determines whether the joint has PID in order to be controlled via PID position/effort controller. Takes no value: *\<hasPID/\>* means that the mimic joint is controlled via PID. Ommit it so that the mimic joint is controlled via setAngle.
###DisableLinkPlugin
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
-
-using std::string;
-
namespace gazebo
{
class DisableLinkPlugin : public ModelPlugin
private:
// Parameters
- string link_name_;
+ std::string link_name_;
bool kill_sim;
};
}
-#endif
\ No newline at end of file
+#endif
#include <roboticsgroup_gazebo_plugins/disable_link_plugin.h>
-using namespace gazebo;
+namespace gazebo
+{
DisableLinkPlugin::DisableLinkPlugin()
{
void DisableLinkPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf )
{
- this->model_ = _parent;
- this->world_ = this->model_->GetWorld();
+ model_ = _parent;
+ world_ = model_->GetWorld();
// Check for link element
if (!_sdf->HasElement("link"))
ROS_WARN("Link %s not found!", link_name_.c_str());
}
-GZ_REGISTER_MODEL_PLUGIN(DisableLinkPlugin);
\ No newline at end of file
+GZ_REGISTER_MODEL_PLUGIN(DisableLinkPlugin);
+
+}
#include <roboticsgroup_gazebo_plugins/mimic_joint_plugin.h>
-using namespace gazebo;
+namespace gazebo
+{
MimicJointPlugin::MimicJointPlugin()
{
}
}
-GZ_REGISTER_MODEL_PLUGIN(MimicJointPlugin);
\ No newline at end of file
+GZ_REGISTER_MODEL_PLUGIN(MimicJointPlugin);
+
+}