Unexpected Dynamics for Vehicles
I am using Hydro on Gazebo 1.9. I have made a utility vehicle model that is based off of the DRC Vehicle (using the DRC Vehicle/Vehicle ROS plugins). I am currently trying to match the dynamics of the model as closely as possible to the actual, real vehicle that I have. I get the Gazebo vehicle to move by applying a command rotational velocity to the back wheels through gazebomsgs::LinkState /gazebo/setlink_state. The thing that is strange to me is that whether I give a small or large command velocity, it always takes approximately 2 seconds for the settling time to reach the command velocity. This means that if I give a small command velocity, the acceleration is small and if I give a large command velocity, the acceleration is large. I would think that the vehicle would take more time to reach a higher command velocity - is there any way I can make this more realistic? I've tried different types of vehicles and this behavior is consistent. I've also thought about giving command velocity as steps but since it always take 2 seconds to get to the command velocity, I wouldn't be able to get to a desired total time of like 3 seconds, only multiples of 2.
Thanks in advance for any advice you can provide!
EDIT: my drive node
int main(int argc, char **argv)
{
ros::init(argc, argv, "toro_gazebo_drive_pub");
ros::NodeHandle n;
ros::Publisher publ = n.advertise<gazebo_msgs::LinkState>("/gazebo/set_link_state", 1000);
ros::Publisher publ2 = n.advertise<gazebo_msgs::LinkState>("/gazebo/set_link_state", 1000);
ros::Rate loop_rate(20);
while(ros::ok())
{
gazebo_msgs::LinkState msg; //gazebo_msgs::ApplyJointEffortTEST
gazebo_msgs::LinkState msg2; //for second back wheel
double mpers = 0.5; // m/s of vehicle
msg.link_name = "drc_vehicle_xp900::toro::rear_left_wheel"; // husky::back_left_wheel
msg.pose.position.x = 0.0; // don't edit position.x though angular.x
msg.pose.position.y = 0.0;
msg.pose.position.z = 0.0;
msg.pose.orientation.x = 0.0;
msg.pose.orientation.y = 0.0;
msg.pose.orientation.z = 0.0;
msg.pose.orientation.w = 1.0;
msg.twist.linear.x = 0.0;
msg.twist.linear.y = 0.0;
msg.twist.linear.z = 0.0;
msg.twist.angular.x = 0.0;
msg.twist.angular.y = 2.3875*mpers*10; // can modify this to move (+ = forward, - = backward), 2.3875 is for .1m/s
msg.twist.angular.z = 0.0;
msg.reference_frame = "drc_vehicle_xp900::toro::rear_left_wheel"; // husky::back_left_wheel
msg2.link_name = "drc_vehicle_xp900::toro::rear_right_wheel"; // husky::back_right_wheel
msg2.pose.position.x = 0.0; // don't edit position.x though angular.x
msg2.pose.position.y = 0.0;
msg2.pose.position.z = 0.0;
msg2.pose.orientation.x = 0.0;
msg2.pose.orientation.y = 0.0;
msg2.pose.orientation.z = 0.0;
msg2.pose.orientation.w = 1.0;
msg2.twist.linear.x = 0.0;
msg2.twist.linear.y = 0.0;
msg2.twist.linear.z = 0.0;
msg2.twist.angular.x = 0.0;
msg2.twist.angular.y = 2.3875*mpers*10; // can modify this to move ...
Is there any rhyme or reason as to how questions get answered in this forum? Like for my question, did I 1) write a confusing question? 2) ask a question that no one knows the answer to? 3) ask a dumb question? 4) just not wait long enough for a response?
The reason I ask this is because I've tried a number of different ways and spent a lot of time trying to adjust my model/world and if I can't get this to work then I need to drop the Gazebo side of my project.
are you setting joint velocity or applying effort at joint to achieve a velocity?
I'm setting a link velocity through the topic, gazebomsgs::LinkState, to the two rear wheel links. I was trying to use gazeboros in a way that only used topic/msgs without any services/srvs. I've edited my post so that I show the node that I use to drive the vehicle.
setting joint [link] velocity bypasses dynamics, so resulting behavior will not obey newton's second law. To make use of physics and dynamics properly, I recommend creating a PID controller to set joint effort commands and use joint velocity as feedback. One approach I might take is by writing a model plugin (http://gazebosim.org/tutorials?tut=pluginsmodel&cat=writeplugin) to do this.
Ohhh, ok, I didn't know that that bypasses dynamics. For the model plugin method, do you have an example of giving a joint effort w/ or w/o PID control? I know that tutorial link applies a linear velocity and not an effort.
Well, set velocity with ODE uses a linear motor, and the effect is that the solver finds a *sufficient force* to achieve velocity requested, so not exactly real-world like.
Ok, so I think I'm a bit confused. Should I be setting velocity using 'this->model->SetLinearVel' to get to my command velocity in a plugin, or is there a different set command for setting effort that I should use instead? Is there some reference/wiki where I can learn about the code to use for plugins (I found the bitbucket page for gazebo plugin examples but those don't have a lot of motion other than model_push)? And then, how can I get ROS to communicate with the Gazebo plugin to give...
...a command velocity or effort? I know that there is the 'Using Gazebo plugins with ROS' wiki page but that only deals with sensor plugins and skid steer/differential drive. (I am using SDF for my model and not URDF).
To guarantee that an effort is applied on every simulation step, ModelPlugin approach is preferred. Use Joint::SetForce call (https://bitbucket.org/osrf/gazebo/src/6592c20d6b458911b17c2797364fec6b8365d199/gazebo/physics/Joint.hh?at=gazebo1.9#cl-267) to apply joint efforts. I don't have a simple example handy at the moment, maybe someone else watching this thread does? Another alternative is to to use roscontrol (http://wiki.gazebosim.org/wiki/Tutorials/1.9/ROSControlwith_Gazebo)