Skip to content

Sec. 2: Driving the Husky robot in Gazebo

SMART Lab at Purdue University edited this page Jun 28, 2018 · 2 revisions

Driving the Husky robot in Gazebo simulation

Run Simulation

Run roscore first:

 roscore

Open another terminal, and launch:

 roslaunch husky_gazebo husky_empty_world.launch

You will see the Husky in the empty world.

Move the Husky robot

We can now command the Husky to go forwards. Open a terminal window, and use the command below, copy pasting this one won’t work! You can tab complete this command by hitting the tab key after geometry_msgs/Twist:

 rostopic pub /husky_velocity_controller/cmd_vel geometry_msgs/Twist "linear:
    x: 0.5
    y: 0.0
    z: 0.0
 angular:
    x: 0.0
    y: 0.0
    z: 0.0" -r 10

In the above command, we publish to the /husky_velocity_controller/cmd_vel topic, of topic type geometry_msgs/Twist. The data we publish tells the simulated Husky to go forwards at 0.5m/s, without any rotation. You should see your Husky move forwards.

Example 1 - Drive another's robot

This example shows how to send a command through ROS topics between two different computers, pair up with someone else.

Person A - Run the ROS master and Gazebo simulation

You need to configure ROS environment variables to properly communicate between two ROS systems.

First, check your IP address:

ifconfig

and put your IP address:

export ROS_IP=YOUR_IP
export ROS_MASTER_URI=http://YOUR_IP:11311

For example, if your IP address is 128.46.80.123

export ROS_IP=128.46.80.123
export ROS_MASTER_URI=http://128.46.80.123:11311

Then run roscore:

roscore

You will see the following messages in terminal:

SUMMARY
========

PARAMETERS
* /rosdistro: indigo
* /rosversion: 1.11.21

NODES
auto-starting new master
process[master]: started with pid [25586]
ROS_MASTER_URI=http://YOUR_IP:11311

If everything's going well, launch Gazebo

roslaunch gazebo_ros willowgarage_world.launch

You will see the Willow garage world without the robot, spawn a husky:

roslaunch husky_gazebo spawn_husky.launch

Person A is done! Now let's prepare for Person B!

Person B - Command the robot

To connect the ROS master, configure ROS environment variables. See your IP address:

ifconfig

and put your IP address and the master address from above:

export ROS_IP=YOUR_IP
export ROS_MASTER_URI=http://MASTER_IP:11311

For example, if your (Person B) IP address is 128.46.80.10 and the master IP is 128.46.80.123 (Person A)

export ROS_IP=128.46.80.10
export ROS_MASTER_URI=http://128.46.80.123:11311

To make sure the connection, enter:

rostopic list

You will see a bunch of topic lists such as:

/cmd_vel
/husky_velocity_controller/cmd_vel
/husky_velocity_controller/odom
....

If you've done with the previous tasks, you could move the Husky using the keyboard:

 rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Explore the Willow garage and change the role!

Example 2 - Escape the Willow Garage

This example demonstrates how to control multiple robots simultaneously. One person runs the ROS master and Gazebo simulation and the others send a command to control their robot.

Person A - Run the ROS master and Gazebo simulation

Configure ROS environments like we did above and run roscore:

 roscore

Launch the Gazebo:

 roslaunch gazebo_ros willowgarage_world.launch

Spawn a robot at the origin (0,0):

 roslaunch gazebo_plugins pioneer3dx.gazebo.launch

Spawn another robot at a different pose (0,-2) to avoid crashes:

 ROBOT_INITIAL_POSE="-y -2" roslaunch husky_gazebo spawn_husky.launch

Person B and Person C - Command each Robot

Pick one of the robots, Husky or P3dx. If you wish to control the P3dx, enter:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=p3dx/cmd_vel

If you wish to control the Husky, enter:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=husky_velocity_controller/cmd_vel

Compete who escape the Willow garage first!

Design a feedback controller

We will design a simple feedback controller to drive a robot to reach the goal location. In general, autonomous navigation represents a multi-layered embedded system that has the following abilities:

  • to generate an optimal path without collisions,

  • to follow the path generated with desired pose and location,

  • to compute an alternative path if necessary.

In this tutorial, we will design a simple controller that receives the desired destination from the user and publishes command messages to the robot.

Go to the gazebo_tutorial ROS package in this repository and download nre_simhuskycontrol.py to your device.

https://github.com/SMARTlab-Purdue/ros-tutorial-gazebo-simulation/blob/master/gazebo-tutorial/scripts/nre_simhuskycontrol.py

This controller allows you to adjust controller parameters, proportional gains, and goals. By tuning those variables, you will be able to see better control performance. The controller works in the following algorithm.

  1. Calculate difference between current and desired locations. From line 32:

    distance = sqrt((pose[0]-goal[0])**2+(pose[1]-goal[1])**2)
    
  2. If distance is below a threshold, stop the robot. OR if distance is above the threshold, set yaw angle to orient robot toward desired location, and drive towards it. From line 33:

    if (distance > distThresh):
          v = vconst
          desireYaw = atan2(goal[1]-pose[1],goal[0]-pose[0])
          u = desireYaw-theta
          bound = atan2(sin(u),cos(u))
          w = min(0.5 , max(-0.5, wgain*bound))
    

The algorithm is illustrated in the following image.

Sim model

Test your controller

Run roscore first:

 roscore

Open another terminal, and launch:

 roslaunch husky_gazebo husky_empty_world.launch

You will see the Husky in the empty world. To monitor the real-time position data, run:

rostopic echo /odometery/filtered

Go to the folder that includes nre_simhuskycontrol.py and run the controller:

 python nre_simhuskycontrol.py

The Husky will not move because the goal is now (0,0). Change the goal in the script and rerun nre_simhuskycontrol.py. For example, the robot will stop as soon as it gets close to the destination at (10,10). You could see your robot has stopped at the destination and the odometry data is close to (10,10) within the distThresh that you defined.

Let's run the controller again with different parameters (wgain, vconst, distThresh).