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>
41 void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
64 std::string link_name;
66 if (_sdf->HasElement(
"wheelLinkName"))
68 link_name = _sdf->Get<std::string>(
"wheelLinkName");
78 ROS_FATAL(
"The mecanum plugin requires a `wheelLinkName` parameter.");
82 if (_sdf->HasElement(
"fixedLinkName"))
84 link_name = _sdf->Get<std::string>(
"fixedLinkName");
94 ROS_FATAL(
"The mecanum plugin requires a `fixedLinkName` parameter.");
98 if (_sdf->HasElement(
"rollerAngle"))
107 if (_sdf->HasElement(
"rollerFriction"))
116 if (_sdf->HasElement(
"rollerSkidFriction"))
126 ", referenced to " <<
fixed_link_->GetName() <<
", with a roller " <<
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();
143 unsigned int collision_index = 0;
144 physics::SurfaceParamsPtr surface =
wheel_link_->GetCollision(collision_index)->GetSurface();
147 physics::ODESurfaceParams* ode_surface =
dynamic_cast<physics::ODESurfaceParams*
>(surface.get());
148 physics::FrictionPyramid& fric(ode_surface->frictionPyramid);