Robotics StackExchange | Archived questions

Why are Physics implementations always in plugins ?

I have observed both the Ackermann steering and wishbone suspension implementations. Why are most examples of the physics always within plugins i.e. virtual implementations. Is Gazebo capable of implementing the above using pure geometry and joints ? Are there implementations of this ?

Asked by pchidamb on 2017-09-27 14:20:52 UTC

Comments

Answers

Why are most examples of the physics always within plugins i.e. virtual implementations?
The short answer is it's generally easier/better to implement an empirical behavioral model for an entire subsystem (e.g. a drive train) using a plugin, then it is to painstakingly model the subsystem part-by-part in a physics simulator.

More moving parts = more complexity, slower simulation, more things that can break (explode) in your model.

Is Gazebo capable of implementing the above using pure geometry and joints?
Based on my (albeit) limited experience so far, yes! You should be able to implement both Ackermann steering and wishbone suspension using Gazebo. That being said, the end result may not be pretty/stable...

I think the critical questions for you are:
1) can a Gazebo implementation provide value over and above a quick-and-dirty plugin implementing an empirical behavioral model and
2) is it worth the time/effort?

Are there implementations of this?
Not that I know of. Every project I've seen so far uses plugins to represent suspensions, fluidic effects, steering, etc...

Further Resources
I highly recommend checking out the Gazebo URDF tutorial: http://gazebosim.org/tutorials/?tut=ros_urdf
skimming the Open Dynamics Engine (ODE) User Guide: http://www.ode.org/ode-latest-userguide.html
and watching this 2014 ROSCON talk by Steve Peters about the different Physics engines: https://vimeo.com/107517366
to get a better understanding of Gazebo's underlying mechanisms.

Finally, good luck!

EDIT:
You may also be interested in this video of a car with an Ackermann steering Gazebo plugin: https://www.youtube.com/watch?v=WlFdLkD3wa8

The author - Yossi Cohen - posted the following comment in response to a viewer:
"
here is the code:
apply_steering is called in update.

steering request is the angle of the inner wheel
the wheels steering is controlled using a variant of PID.
It's from a hmmwv model i made with active wishbone suspension and programatical ackerman steering

  void apply_steering()  
  {  
    double ThetaAckerman = 0;  
    if (Steering_Request > 0) //turning right  
    {  
      ThetaAckerman = atan(1 / ((1 / (tan(Steering_Request)) + (VehicleWidth / VehicleLength))));  
      steer_controller(this->streer_joint_left_1, Steering_Request);  
      steer_controller(this->streer_joint_right_1, ThetaAckerman);  
    }  
    else if (Steering_Request < 0) //turning left  
    {  
      ThetaAckerman = atan(1 / ((1 / (tan(-Steering_Request)) + (VehicleWidth / VehicleLength))));  
      steer_controller(this->streer_joint_left_1, -ThetaAckerman);  
      steer_controller(this->streer_joint_right_1, Steering_Request);  
    }  
    else  
    {  
      steer_controller(this->streer_joint_left_1, 0);  
      steer_controller(this->streer_joint_right_1, 0);  
    }  

    //  std::cout << ThetaAckerman << std::endl;  
  }  
  void steer_controller(physics::JointPtr steer_joint, double Angle)  
  {  
    // std::cout << " getting angle"<< std::endl;  
    std_msgs::Float64 msg;  
    double currentWheelAngle = steer_joint->GetAngle(0).Radian();  
    double steeringOmega = steer_joint->GetVelocity(0);  
    if (steer_joint == this->streer_joint_left_1) //controlling left wheel  
    {  
      DesiredAngle = DesiredAngle + steeringSpeed * deltaSimTime * (Angle - DesiredAngle);  
      if (fabs(Angle - DesiredAngle)<0.05)DesiredAngle=Angle;  
      IerL+=DesiredAngleR - currentWheelAngle;  
      double jointforce = control_P * (DesiredAngle - currentWheelAngle)+control_I*IerL - control_D * (steeringOmega);  
      steer_joint->SetForce(0, jointforce); 
      //  std::cout << currentWheelAngle<< std::endl;  
    }  
    else //controlling right wheel  
    {  
      DesiredAngleR = DesiredAngleR + steeringSpeed * deltaSimTime * (Angle - DesiredAngleR);  
      if (fabs(Angle - DesiredAngleR)<0.05)DesiredAngleR=Angle;  
      IerR+=DesiredAngleR - currentWheelAngle;  
      double jointforce = control_P * (DesiredAngleR - currentWheelAngle)+control_I*IerR - control_D * (steeringOmega);  
      steer_joint->SetForce(0, jointforce);  
    }  
    // std::cout << "efforting"<< std::endl;  
    // this->jointController->SetJointPosition(steer_joint, Angle*0.61);  
  }  

"

Asked by josephcoombe on 2017-09-27 15:56:27 UTC

Comments