Regarding upper and lower limits in revolute joint.
Hi,
I am using an SDF world with a model plugin. I am using a revolute joint with certain upper and lower limits for joint position, specified in radians. However, when I am applying higher forces, the links are passing that limit by a small amount (when I have set the limits 1.5, it is going until 1.6 in both directions). I am not sure what else to do, or if I am doing something wrong. Below are the relevant snippets of my sdf file and plugin code. Please suggest the needful. Thanks.
Sdf code for joint:
<joint name='Body_to_ch1' type='revolute'>
<parent>Body</parent>
<child>ch1</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<use_parent_model_frame>0</use_parent_model_frame>
<limit>
<lower>-1.5</lower>
<upper>1.5</upper>
<effort>0.1</effort>
<velocity>1000</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
</joint>
Plugin code:
#include <functional>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
#include <ignition/math/Vector3.hh>
#include <math.h>
int i = 0;
double w = 50*3.14;
double A = 1.0;
double forceamp = 0.0006295;
double t = 0;
double dt = 0.0001;
double torque = 0;
namespace gazebo
{
class ModelPush : public ModelPlugin
{
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
{
this->model = _parent;
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
std::bind(&ModelPush::OnUpdate, this));
}
// Called by the world update start event
public: void OnUpdate()
{
torque = forceamp*cos(w*t);
this->model->GetJoint("Body_to_ch1")->SetForce(0,torque);
t = t + dt;
}
private: physics::ModelPtr model;
private: event::ConnectionPtr updateConnection;
};
GZ_REGISTER_MODEL_PLUGIN(ModelPush)
}
Try increasing the effort and decreasing the velocity. I'm assuming 1000 rad/sec is not really what you want.
Thanks for the suggestion. I tried that and it is still passing the limits. However, I realized that rotation order matters, and it appeared like limits are being passed by a large amount. I printed the position and I found that when I have set the limits to 1.5, it doesn't go beyond 1.6. But it is still passing the limits. Also, I need speeds of the order of around 500 rad/sec.