Gazebo | Ignition | Community
Ask Your Question
1

Modfy a joints friction value deuring exacution

asked 2018-06-08 01:04:29 -0500

tonka46 gravatar image

The platform I have has an un-actuated joint that can lock or unlock and be passively actuated by other joints. I was hoping to simulate the locking and unlocking modifying the joints friction value, very large for locked and small for unlocked. Is there a way to modify the friction value during simulation?

I have looked through rosservice and rospram with no luck is this possible from gazebo? or is there a better way of solving this problem?

<joint type="continuous" name="shoulder_joint"> <parent link="base_link"/> <child link="shoulder_conection"/> <origin xyz="0 0 0"/> <axis xyz="0 0 1"/> <dynamics damping="0.0" friction="5000.0"/> </joint>

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-06-18 19:16:57 -0500

tonka46 gravatar image

Gazebo does support this functionality for ODE revolute, prismatic, and universal joints refer pull request https://bitbucket.org/osrf/gazebo/pul... for details. This also highlights the interaction between fmax and friction and not to set them at the same time.

To avoid the conflict of setting fmax and friction while maintaining existing functionality I copied SetJointProperties.srv and ODEJointProperties.msg making SetJointFriction.srv and ODEJointFriction.msg

SetJointFriction.srv

string joint_name                               # name of joint
gazebo_msgs/ODEJointFriction ode_joint_config # access to ODE joint dynamics properties
---
bool success                                    # return true if get successful
string status_message                           # comments if available

ODEJointFriction.msg

# access to low level joint properties, change these at your own risk
float64[] friction            # joint friction

gazebo_ros_api_plugin.cpp was modified by copying setJointProperties() to create

bool GazeboRosApiPlugin::setJointFriction(gazebo_msgs::SetJointFriction::Request &req,
                                        gazebo_msgs::SetJointFriction::Response &res)
{
  /// @todo: current settings only allows for setting of 1DOF joints (e.g. HingeJoint and SliderJoint) correctly.
  gazebo::physics::JointPtr joint;
#if GAZEBO_MAJOR_VERSION >= 8
  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
  {
    joint = world_->ModelByIndex(i)->GetJoint(req.joint_name);
#else
  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
  {
    joint = world_->GetModel(i)->GetJoint(req.joint_name);
#endif
    if (joint) break;
  }

  if (!joint)
  {
    res.success = false;
    res.status_message = "SetJointFriction: joint not found";
    return true;
  }
  else
  {

    for(unsigned int i=0;i< req.ode_joint_config.friction.size();i++)
      joint->SetParam("friction",i,req.ode_joint_config.friction[i]);

    res.success = true;
    res.status_message = "SetJointFriction: properties set";
    return true;
  }
}

finally, duplicate the service advertisers

edit flag offensive delete link more

Comments

Archived version of the Bitbucket PR referenced in this answer can be found at:

https://osrf-migration.github.io/gaze...

danzimmerman gravatar imagedanzimmerman ( 2023-03-22 19:18:52 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-06-08 01:04:29 -0500

Seen: 441 times

Last updated: Jun 18 '18