Is it possible to apply force/Set velocity or set position on ball joint?
Hi,
I am using Gazebo 9 and ROS Melodic. I am trying to develop a robot which has 2 ball joints (using an sdf file). I wrote a model plugin for setting force (torque) and position (angular position) for each of these joints using joint->SetForce and joint->SetPosition functions, however, nothing happened. I changed the index from 0 to 1 & 2 but nothing seems to be working. However, when I change the joint type to revolute, I am able to apply force and set position of the joints. Please suggest if I can set the force and position for a ball joint using sdf format and a model plugin or not. If there is no way, what is the alternate of using a ball joint as I need to model a ball joint for my robot and apply torques/change positions and velocities around all the three axes. I was thinking of three revolute joints but that is not working for same parent and child for all the three revolute joints. Below are my code for sdf file and whole code for the plugin. Please let me know if full code for sdf is required. Thank you.
For defining joint in sdf file:
<joint name='Body_to_RW_Z' type='revolute'>
<parent>Body</parent>
<child>RW</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</lower>
<upper>1</upper>
<effort>100</effort>
<velocity>100</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.2</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
Code for plugin:
/#include <functional>
/#include <gazebo/gazebo.hh>
/#include <gazebo/physics/physics.hh>
/#include <gazebo/common/common.hh>
/#include <ignition/math/Vector3.hh>
int i = 0;
namespace gazebo
{
class ModelPush : public ModelPlugin
{
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
{
// Store the pointer to the model
this->model = _parent;
// Listen to the update event. This event is broadcast every
// simulation iteration.
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
std::bind(&ModelPush::OnUpdate, this));
}
// Called by the world update start event
public: void OnUpdate()
{
// Apply a small linear velocity to the model.
//this->model->SetLinearVel(ignition::math::Vector3d(0, 0, 0));
this->model->GetJoint("Body_to_RW_Z")->SetParam("fmax",0, 1000000000);
this->model->GetJoint("Body_to_LW_Z")->SetParam("fmax",0, 1000000000);
if (i < 10)
{//this->model->GetJoint("Body_to_LW_Z")->SetForce(0,0.05);
//this->model->GetJoint("Body_to_LW_Z")->SetForce(1,0.05);
//this->model->GetJoint("Body_to_RW_Z")->SetForce(0,0.05);
this->model->GetJoint("Body_to_RW_Z")->SetPosition(0,i*0.1,false);
//this->model->GetJoint("Body_to_LW_Z")->SetPosition(0,0,false);
this->model->GetJoint("Body_to_LW_Z")->SetPosition(1,i*0.1,false);
}
else
{//this->model->GetJoint("Body_to_LW_Z")->SetForce(0,-0.05);
//this->model->GetJoint("Body_to_LW_Z")->SetForce(1,-0.05);
//this->model->GetJoint("Body_to_RW_Z")->SetForce(0,-0.05);
this->model->GetJoint("Body_to_RW_Z")->SetPosition(0,-1*(i-10)*0.1,false);
// this->model->GetJoint("Body_to_LW_Z")->SetPosition(0,0,false ...