Programs that show how to drive a Pioneer3-AT robot with ros.
This README is adapted from this google doc, which has some better formatting and diagrams if the instructions here are confusing.
This is a quick-start guide to using a Pioneer3AT Mobile Robot with ROS. It should allow you to drive a robot via a GUI application or a PS3 controller. If you have a SICK or Hokuyo LMS device, you can also make a 2D map of an environment and be able to give the robot Autonomous navigation commands from a GUI application.
If you have any problems, get stuck, lost, confused, find errors, just want to say thanks, etc, highlight the area of the document and leave a comment. I’ll try to keep this up to date as best as I can whenever I receive feedback. :)
Install wiki page works well: http://www.ros.org/wiki/melodic/Installation/Ubuntu Select the -desktop-full package. https://docs.google.com/document/d/1-HmQuTe955WDy5t9Q70rw00o4WJjFePuAhqxbgarA1Q/edit
Check the ROS website for installing and setting up the workspace
Apparently, Gazebo 9 a new set of dependencies from Ignition was introduced. Follow these instructions to download them.
cd ~/catkin_ws/src
git clone https://github.com/amor-ros-pkg/rosaria.git
cd ..
rosdep install rosaria
catkin_make
source ~/.bashrc
cd ~/catkin_ws/src
git clone git://github.com/dawonn/ros-pioneer3at.git
cd ..
rosdep install pioneer3at
catkin_make
source ~/.bashrc
For directions that required Gazebo 1.6, see the google doc.
Follow the instructions at gazebosim.org for download and installation.
echo "export LD_LIBRARY_PATH=/usr/local/lib:$LD_LIBRARY_PATH" >> ~/.bashrc
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
This line may depend on how you install it.
source ~/.bashrc
gazebo
- Click the insert tab on the top left of the screen
- Expand the ‘Model Database’
- Insert a Pioneer 3AT model into the world
- Insert a Willow Garage model into the world
- Close Gazebo
Note: This process downloads a copy of the models to ~/.gazebo/models/
gedit ~/catkin_ws/src/ros-pioneer3at/launch/hardware.launch
(gedit can be replaced with any text editor)
- Comment the physical robot and lidar drivers
- Uncomment the gazebo robot and lidar drivers
<!-- Select the robot-driver you wish to use -->
<include file="$(find pioneer3at)/launch/core/gazebo.launch" />
<!-- <include file="$(find pioneer3at)/launch/core/rosaria.launch" /> -->
<!-- <include file="$(find pioneer3at)/launch/core/p2os_driver.launch" /> -->
<!-- Select the laser you wish to use -->
<include file="$(find pioneer3at)/launch/lidar/gazebo_hokuyo.launch" />
<!-- <include file="$(find pioneer3at)/launch/lidar/sicklms.launch" /> -->
<!-- <include file="$(find pioneer3at)/launch/lidar/hokuyo.launch" /> -->
gedit ~/catkin_ws/src/ros-pioneer3at/launch/ui.launch
- Select the control method you want to use.
<!-- Select the control method you wish to use -->
<include file="$(find pioneer3at)/launch/control/rqt_robot_steering.launch" />
<!-- <include file="$(find pioneer3at)/launch/control/ps3joy.launch" /> -->
<!-- <include file="$(find pioneer3at)/launch/control/xboxjoy.launch" /> -->
sudo gedit ~/.gazebo/models/pioneer3at/model.sdf
- Uncomment the skidsteerdrive plugin near the bottom:
- Remove the tag
- Add the following:
<include>
<uri>model://hokuyo</uri>
<pose>0.2 0 0.13 0 0 0</pose>
</include>
<joint name="hokuyo_joint" type="revolute">
<child>hokuyo::link</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
This demo is the most basic example; you can send movement messages to the robot along the /Pioneer3AT/cmd_vel
topic.
cd catkin_ws/src/pioneer3at/launch/
roslaunch hardware.launch
Then, in another terminal:
gzclient
File paths here are all prefixed by ~catkin_ws/src/pioneer3at
.
launch/hardware.launch
runs launch/core/gazebo.launch
.
gazebo.launch
in turn opens a world (config/gazebo/wg_world.sdf
) with all the models needed in a gazebo server, and runs a ROS node from src/gazebo_bridge.cc
that connects Gazebo to ROS communication so the robot can be controlled.
hardware.launch
then enables the laser attached to the robot model with launch/lidar/gazebo_hokuyo.launch
.
gazebo_hokuyo.launch
runs a laser-scanning ROS node from src/gazebo_laserscan.cc
which publishes information from the laser sensor.
Finally, hardware.launch
runs launch/core/urdf.launch
and cmd_vel_mux.launch
. The first opens a ROS node that publishes location+orientation information about the robot, and the second seems to remap a ROS topic so robot-control commands can be communicated along Pioneer3AT/cmd_vel. (This information should be reviewed).
If you want to run more complex examples, check out demo_navigation_amcl.launch
and demo_navigation_gmapping.launch
.