mimic_joint_plugin.cpp
Go to the documentation of this file.
1 
24 
25 #if GAZEBO_MAJOR_VERSION >= 8
26 namespace math = ignition::math;
27 #else
28 namespace math = gazebo::math;
29 #endif
30 
31 namespace gazebo {
32 
34  {
35  joint_.reset();
36  mimic_joint_.reset();
37  }
38 
40  {
41  update_connection_.reset();
42  }
43 
44  void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
45  {
46  model_ = _parent;
47  world_ = model_->GetWorld();
48 
49  // Error message if the model couldn't be found
50  if (!model_) {
51  ROS_ERROR("Parent model is NULL! MimicJointPlugin could not be loaded.");
52  return;
53  }
54 
55  // Check that ROS has been initialized
56  if (!ros::isInitialized()) {
57  ROS_ERROR("A ROS node for Gazebo has not been initialized, unable to load plugin.");
58  return;
59  }
60 
61  // Check for robot namespace
62  if (_sdf->HasElement("robotNamespace")) {
63  robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>();
64  }
66 
67  // Check for joint element
68  if (!_sdf->HasElement("joint")) {
69  ROS_ERROR("No joint element present. MimicJointPlugin could not be loaded.");
70  return;
71  }
72 
73  joint_name_ = _sdf->GetElement("joint")->Get<std::string>();
74 
75  // Check for mimicJoint element
76  if (!_sdf->HasElement("mimicJoint")) {
77  ROS_ERROR("No mimicJoint element present. MimicJointPlugin could not be loaded.");
78  return;
79  }
80 
81  mimic_joint_name_ = _sdf->GetElement("mimicJoint")->Get<std::string>();
82 
83  // Check if PID controller wanted
84  has_pid_ = _sdf->HasElement("hasPID");
85  if (has_pid_) {
86  std::string name = _sdf->GetElement("hasPID")->Get<std::string>();
87  if (name.empty()) {
88  name = "gazebo_ros_control/pid_gains/" + mimic_joint_name_;
89  }
90  const ros::NodeHandle nh(model_nh, name);
91  pid_.init(nh);
92  }
93 
94  // Check for multiplier element
95  multiplier_ = 1.0;
96  if (_sdf->HasElement("multiplier"))
97  multiplier_ = _sdf->GetElement("multiplier")->Get<double>();
98 
99  // Check for offset element
100  offset_ = 0.0;
101  if (_sdf->HasElement("offset"))
102  offset_ = _sdf->GetElement("offset")->Get<double>();
103 
104  // Check for sensitiveness element
105  sensitiveness_ = 0.0;
106  if (_sdf->HasElement("sensitiveness"))
107  sensitiveness_ = _sdf->GetElement("sensitiveness")->Get<double>();
108 
109  // Get pointers to joints
110  joint_ = model_->GetJoint(joint_name_);
111  if (!joint_) {
112  ROS_ERROR_STREAM("No joint named \"" << joint_name_ << "\". MimicJointPlugin could not be loaded.");
113  return;
114  }
116  if (!mimic_joint_) {
117  ROS_ERROR_STREAM("No (mimic) joint named \"" << mimic_joint_name_ << "\". MimicJointPlugin could not be loaded.");
118  return;
119  }
120 
121  // Check for max effort
122 #if GAZEBO_MAJOR_VERSION > 2
123  max_effort_ = mimic_joint_->GetEffortLimit(0);
124 #else
125  max_effort_ = mimic_joint_->GetMaxForce(0);
126 #endif
127  if (_sdf->HasElement("maxEffort")) {
128  max_effort_ = _sdf->GetElement("maxEffort")->Get<double>();
129  }
130 
131  // Set max effort
132  if (!has_pid_) {
133 #if GAZEBO_MAJOR_VERSION > 2
134  mimic_joint_->SetParam("fmax", 0, max_effort_);
135 #else
136  mimic_joint_->SetMaxForce(0, max_effort_);
137 #endif
138  }
139 
140  // Listen to the update event. This event is broadcast every
141  // simulation iteration.
142  update_connection_ = event::Events::ConnectWorldUpdateBegin(
143  boost::bind(&MimicJointPlugin::UpdateChild, this));
144 
145  // Output some confirmation
146  ROS_INFO_STREAM("MimicJointPlugin loaded! Joint: \"" << joint_name_ << "\", Mimic joint: \"" << mimic_joint_name_ << "\""
147  << ", Multiplier: " << multiplier_ << ", Offset: " << offset_
148  << ", MaxEffort: " << max_effort_ << ", Sensitiveness: " << sensitiveness_);
149  }
150 
152  {
153 #if GAZEBO_MAJOR_VERSION >= 8
154  static ros::Duration period(world_->Physics()->GetMaxStepSize());
155 #else
156  static ros::Duration period(world_->GetPhysicsEngine()->GetMaxStepSize());
157 #endif
158 
159  // Set mimic joint's angle based on joint's angle
160 #if GAZEBO_MAJOR_VERSION >= 8
161  double angle = joint_->Position(0) * multiplier_ + offset_;
162  double a = mimic_joint_->Position(0);
163 #else
164  double angle = joint_->GetAngle(0).Radian() * multiplier_ + offset_;
165  double a = mimic_joint_->GetAngle(0).Radian();
166 #endif
167 
168  if (fabs(angle - a) >= sensitiveness_) {
169  if (has_pid_) {
170  if (a != a)
171  a = angle;
172  double error = angle - a;
173  double effort = math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_);
174  mimic_joint_->SetForce(0, effort);
175  }
176  else {
177 #if GAZEBO_MAJOR_VERSION >= 9
178  mimic_joint_->SetPosition(0, angle, true);
179 #elif GAZEBO_MAJOR_VERSION > 2
180  ROS_WARN_ONCE("The mimic_joint plugin is using the Joint::SetPosition method without preserving the link velocity.");
181  ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model.");
182  ROS_WARN_ONCE("Please set gazebo_pid parameters or upgrade to Gazebo 9.");
183  ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
184  mimic_joint_->SetPosition(0, angle);
185 #else
186  mimic_joint_->SetAngle(0, math::Angle(angle));
187 #endif
188  }
189  }
190  }
191 
193 
194 } // namespace gazebo
gazebo::MimicJointPlugin::mimic_joint_name_
std::string mimic_joint_name_
Definition: mimic_joint_plugin.h:49
gazebo::MimicJointPlugin::MimicJointPlugin
MimicJointPlugin()
Definition: mimic_joint_plugin.cpp:33
gazebo::MimicJointPlugin::max_effort_
double max_effort_
Definition: mimic_joint_plugin.h:50
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
gazebo
gazebo::MimicJointPlugin::model_
physics::ModelPtr model_
Definition: mimic_joint_plugin.h:60
gazebo::MimicJointPlugin::pid_
control_toolbox::Pid pid_
Definition: mimic_joint_plugin.h:54
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
gazebo::MimicJointPlugin::robot_namespace_
std::string robot_namespace_
Definition: mimic_joint_plugin.h:49
gazebo::MimicJointPlugin::offset_
double offset_
Definition: mimic_joint_plugin.h:50
gazebo::MimicJointPlugin::sensitiveness_
double sensitiveness_
Definition: mimic_joint_plugin.h:50
control_toolbox::Pid::init
bool init(const ros::NodeHandle &n, const bool quiet=false)
gazebo::MimicJointPlugin::Load
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) override
Definition: mimic_joint_plugin.cpp:44
gazebo::MimicJointPlugin
Definition: mimic_joint_plugin.h:38
gazebo::MimicJointPlugin::has_pid_
bool has_pid_
Definition: mimic_joint_plugin.h:51
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::MimicJointPlugin::joint_name_
std::string joint_name_
Definition: mimic_joint_plugin.h:49
gazebo::MimicJointPlugin::multiplier_
double multiplier_
Definition: mimic_joint_plugin.h:50
gazebo::MimicJointPlugin::UpdateChild
void UpdateChild()
Definition: mimic_joint_plugin.cpp:151
gazebo::MimicJointPlugin::update_connection_
event::ConnectionPtr update_connection_
Definition: mimic_joint_plugin.h:66
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(DisableLinkPlugin)
mimic_joint_plugin.h
ROS_ERROR
#define ROS_ERROR(...)
gazebo::MimicJointPlugin::mimic_joint_
physics::JointPtr mimic_joint_
Definition: mimic_joint_plugin.h:57
gazebo::MimicJointPlugin::world_
physics::WorldPtr world_
Definition: mimic_joint_plugin.h:63
gazebo::MimicJointPlugin::~MimicJointPlugin
virtual ~MimicJointPlugin() override
Definition: mimic_joint_plugin.cpp:39
control_toolbox::Pid::computeCommand
double computeCommand(double error, double error_dot, ros::Duration dt)
ros::Duration
ros::NodeHandle
gazebo::MimicJointPlugin::joint_
physics::JointPtr joint_
Definition: mimic_joint_plugin.h:57


roboticsgroup_upatras_gazebo_plugins
Author(s): Konstantinos Chatzilygeroudis
autogenerated on Wed Mar 2 2022 00:54:30