Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

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 gazebo_msgs::LinkState /gazebo/set_link_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!

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 gazebo_msgs::LinkState /gazebo/set_link_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 (+ = forward, - = backward)
  msg2.twist.angular.z = 0.0;
  msg2.reference_frame = "drc_vehicle_xp900::toro::rear_right_wheel"; //  husky::back_right_wheel

  publ.publish(msg);
  publ2.publish(msg2);

  ROS_INFO_STREAM("Sending back-wheel drive command:" << " wheels spinning at " << msg.twist.angular.y << " rad/s" << std::endl);//" rotation(z, steer) = " << msg.twist.angular.z << std::endl);

  ros::spinOnce();

  loop_rate.sleep();


  }
  return 0;
}