ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Max velocity of turtlebot

asked 2021-12-26 04:14:42 -0500

Roshan gravatar image

Hello, I have been simulating a turtlebot3 waffle pi in Gazebo, and been using velocities as high as 0.5m/s. Looking at the hardware specifications: https://emanual.robotis.com/docs/en/p..., it says that the max velocity is 0.26 m/s. Does this mean that it can drive at 0.5m/s in the simulations, but not physically because of hardware limitations?

edit retag flag offensive close merge delete

Comments

Hi @Roshan

If the simulation is higher than specs it must be that a configuration file has been changed. I checked from the repo and the simulation matches robot spec:

BURGER_MAX_LIN_VEL = 0.22 BURGER_MAX_ANG_VEL = 2.84

WAFFLE_MAX_LIN_VEL = 0.26 WAFFLE_MAX_ANG_VEL = 1.82

LIN_VEL_STEP_SIZE = 0.01 ANG_VEL_STEP_SIZE = 0.1

https://github.com/ROBOTIS-GIT/turtle...

osilva gravatar image osilva  ( 2021-12-26 06:14:08 -0500 )edit

That's weird, I haven't changed the configuration file, but I can still publish for example 0.5 or 1 into the cmd_vel and see changes. Does the 0.5 I'm publishing into the cmd_vel mean something other than velocity maybe?

Roshan gravatar image Roshan  ( 2021-12-26 06:17:58 -0500 )edit

And here as well: https://github.com/ROBOTIS-GIT/turtle...

#define MAX_LINEAR_VELOCITY             0.22   // m/s
#define MAX_ANGULAR_VELOCITY            2.84   // rad/s
osilva gravatar image osilva  ( 2021-12-26 06:22:22 -0500 )edit

You can publish any speed but the robot will just go to your max speed

osilva gravatar image osilva  ( 2021-12-26 06:24:44 -0500 )edit

I think you may be right:

void Turtlebot3Fake::commandVelocityCallback(const geometry_msgs::TwistConstPtr cmd_vel_msg)
{
  last_cmd_vel_time_ = ros::Time::now();

  goal_linear_velocity_  = cmd_vel_msg->linear.x;
  goal_angular_velocity_ = cmd_vel_msg->angular.z;

  wheel_speed_cmd_[LEFT]  = goal_linear_velocity_ - (goal_angular_velocity_ * wheel_seperation_ / 2);
  wheel_speed_cmd_[RIGHT] = goal_linear_velocity_ + (goal_angular_velocity_ * wheel_seperation_ / 2);
}

https://github.com/ROBOTIS-GIT/turtle...

It never checks against max velocity just checks against published velocity

osilva gravatar image osilva  ( 2021-12-26 06:36:02 -0500 )edit

Ah ok, so that does mean that the simulations don't actually have a max velocity, but once you start using a physical setup the max velocity will be at 0.26 m/s for linear velocity

Roshan gravatar image Roshan  ( 2021-12-26 06:42:06 -0500 )edit

That’s correct. You could add the checks like in the teleop program

osilva gravatar image osilva  ( 2021-12-26 06:49:55 -0500 )edit

Hi @Roshan, Added an answer to complete the cycle and summarize our discussion.

osilva gravatar image osilva  ( 2021-12-27 11:38:22 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2021-12-27 11:37:39 -0500

osilva gravatar image

As keenly observed by @Roshan, the Turtlebot3 simulation linear velocity can be set higher than the physical robot.

The main function:

void Turtlebot3Fake::commandVelocityCallback(const geometry_msgs::TwistConstPtr cmd_vel_msg)
{
  last_cmd_vel_time_ = ros::Time::now();

  goal_linear_velocity_  = cmd_vel_msg->linear.x;
  goal_angular_velocity_ = cmd_vel_msg->angular.z;

  wheel_speed_cmd_[LEFT]  = goal_linear_velocity_ - (goal_angular_velocity_ * wheel_seperation_ / 2);
  wheel_speed_cmd_[RIGHT] = goal_linear_velocity_ + (goal_angular_velocity_ * wheel_seperation_ / 2);
}

https://github.com/ROBOTIS-GIT/turtle...

Doesn't check for:

#define MAX_LINEAR_VELOCITY             0.22   // m/s
#define MAX_ANGULAR_VELOCITY            2.84   // rad/s

found at: https://github.com/ROBOTIS-GIT/turtle...

To simulate accurately, it's suggested to just a check for maximum velocity like in the teleop program:

def checkLinearLimitVelocity(vel):
    if turtlebot3_model == "burger":
      vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL)
    elif turtlebot3_model == "waffle" or turtlebot3_model == "waffle_pi":
      vel = constrain(vel, -WAFFLE_MAX_LIN_VEL, WAFFLE_MAX_LIN_VEL)
    else:
      vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL)

    return vel
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-12-26 04:14:42 -0500

Seen: 1,176 times

Last updated: Dec 27 '21