mecanum_plugin.cpp
Go to the documentation of this file.
1 
26 #include <gazebo/common/Events.hh>
27 #include <gazebo/common/Plugin.hh>
28 #include <gazebo/physics/ode/ODESurfaceParams.hh>
29 #include <gazebo/physics/physics.hh>
30 #include <ros/console.h>
31 
32 #include <string>
33 
34 
35 namespace gazebo
36 {
37 
38 class MecanumPlugin : public ModelPlugin
39 {
40 public:
41  void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
42 
43 protected:
44  virtual void GazeboUpdate();
45 
46 private:
47  event::ConnectionPtr update_connection_;
48  physics::ModelPtr model_;
49  physics::LinkPtr wheel_link_;
50  physics::LinkPtr fixed_link_;
51  double roller_angle_;
54 };
55 
56 // Register this plugin with the simulator
58 
59 void MecanumPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
60 {
61  // Store the model
62  model_ = _parent;
63 
64  std::string link_name;
65 
66  if (_sdf->HasElement("wheelLinkName"))
67  {
68  link_name = _sdf->Get<std::string>("wheelLinkName");
69  wheel_link_ = model_->GetLink(link_name);
70  if (!wheel_link_)
71  {
72  ROS_FATAL_STREAM("Wheel link [" << link_name << "] not found!");
73  return;
74  }
75  }
76  else
77  {
78  ROS_FATAL("The mecanum plugin requires a `wheelLinkName` parameter.");
79  return;
80  }
81 
82  if (_sdf->HasElement("fixedLinkName"))
83  {
84  link_name = _sdf->Get<std::string>("fixedLinkName");
85  fixed_link_ = model_->GetLink(link_name);
86  if (!fixed_link_)
87  {
88  ROS_FATAL_STREAM("Fixed link [" << link_name << "] not found!");
89  return;
90  }
91  }
92  else
93  {
94  ROS_FATAL("The mecanum plugin requires a `fixedLinkName` parameter.");
95  return;
96  }
97 
98  if (_sdf->HasElement("rollerAngle"))
99  {
100  roller_angle_ = _sdf->Get<double>("rollerAngle");
101  }
102  else
103  {
104  roller_angle_ = M_PI / 4;
105  }
106 
107  if (_sdf->HasElement("rollerFriction"))
108  {
109  roller_friction_ = _sdf->Get<double>("rollerFriction");
110  }
111  else
112  {
113  roller_friction_ = 100;
114  }
115 
116  if (_sdf->HasElement("rollerSkidFriction"))
117  {
118  roller_skid_friction_ = _sdf->Get<double>("rollerSkidFriction");
119  }
120  else
121  {
122  roller_skid_friction_ = 100000;
123  }
124 
125  ROS_INFO_STREAM("Mecanum plugin initialized for " << wheel_link_->GetName() <<
126  ", referenced to " << fixed_link_->GetName() << ", with a roller " <<
127  "angle of " << roller_angle_ << " radians.");
128 
129  // Register update event handler
130  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
131  boost::bind(&MecanumPlugin::GazeboUpdate, this));
132 }
133 
135 {
136  math::Pose wheel_pose = wheel_link_->GetWorldCoGPose();
137  math::Pose fixed_pose = fixed_link_->GetWorldCoGPose();
138  math::Quaternion wheel_orientation = wheel_pose.CoordRotationSub(fixed_pose.rot);
139  double wheel_angle = wheel_orientation.GetPitch();
140  ROS_DEBUG_STREAM(wheel_link_->GetName() << " angle is " << wheel_angle << " radians.");
141 
142  // TODO: Understand better what the deal is with multiple collisions on a link.
143  unsigned int collision_index = 0;
144  physics::SurfaceParamsPtr surface = wheel_link_->GetCollision(collision_index)->GetSurface();
145 
146  // TODO: Check that the physics engine is ODE to avoid a segfault here.
147  physics::ODESurfaceParams* ode_surface = dynamic_cast<physics::ODESurfaceParams*>(surface.get());
148  physics::FrictionPyramid& fric(ode_surface->frictionPyramid);
149 
150  // TODO: Parameterize these.
151  fric.SetMuPrimary(roller_skid_friction_);
152  fric.SetMuSecondary(roller_friction_);
153 
154  // TODO: Investigate replacing this manual trigonometry with Pose::rot::RotateVector. Doing this
155  // would also make it easier to support wheels which rotate about an axis other than Y.
156  fric.direction1.x = cos(roller_angle_) * cos(wheel_angle);
157  fric.direction1.y = sin(roller_angle_);
158  fric.direction1.z = cos(roller_angle_) * sin(wheel_angle);
159 }
160 
161 } // namespace gazebo
gazebo
Definition: mecanum_plugin.cpp:35
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
gazebo::MecanumPlugin::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: mecanum_plugin.cpp:59
gazebo::MecanumPlugin::model_
physics::ModelPtr model_
Definition: mecanum_plugin.cpp:48
gazebo::MecanumPlugin::roller_skid_friction_
double roller_skid_friction_
Definition: mecanum_plugin.cpp:53
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(MecanumPlugin)
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
console.h
gazebo::MecanumPlugin
Definition: mecanum_plugin.cpp:38
gazebo::MecanumPlugin::wheel_link_
physics::LinkPtr wheel_link_
Definition: mecanum_plugin.cpp:49
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ROS_FATAL
#define ROS_FATAL(...)
gazebo::MecanumPlugin::fixed_link_
physics::LinkPtr fixed_link_
Definition: mecanum_plugin.cpp:50
gazebo::MecanumPlugin::update_connection_
event::ConnectionPtr update_connection_
Definition: mecanum_plugin.cpp:47
gazebo::MecanumPlugin::roller_angle_
double roller_angle_
Definition: mecanum_plugin.cpp:51
gazebo::MecanumPlugin::roller_friction_
double roller_friction_
Definition: mecanum_plugin.cpp:52
gazebo::MecanumPlugin::GazeboUpdate
virtual void GazeboUpdate()
Definition: mecanum_plugin.cpp:134


mecanum_gazebo_plugin
Author(s): Mike Purvis
autogenerated on Wed Mar 2 2022 00:52:39