G’day,
Now some advance stuff after touching the surface of ROS. But it should feel good to have something up and running. Now let’s try to run a simulated robot with ROS. Sounds pretty cool, doesn’t it? We will be using the following components in our simulation.
Before we start, I should say a nightmare doesn’t come even close to the ordeal this would put you through. So it’s quite important to get this right. Otherwise you can end up in a whole heap of trouble. I’m not going to explain how to set them up in detail. But I will try my best to point out where you can go wrong.
cmake
, make sure these cmake variables are correctly set. -DBUILD_ROS_SUPPORT=ON
(controls the build of ROS support in MORSE)-DPYMORSE_SUPPORT=ON
(pymorse is a required to implement Morse with python)-DCMAKE_BUILD_TYPE=Release
and optionally,
-DCMAKE_INSTALL_PREFIX
(Installation path for MORSE ($MORSE_ROOT).Might come in handy if you don’t have sudo)-DPYTHON_EXECUTABLE
(Point to python having version >= 3.2. If you want to find where python is, try which python3
)morse check
. You should get the following output.
* Checking up your environment... * Running on Linux. Alright. * Found MORSE libraries in '/usr/local/lib/python3/dist-packages/morse/blender'. Alright. * Trying to figure out a prefix from the script location... * Default scene found. The prefix seems ok. Using it. * Setting $MORSE_ROOT environment variable to default prefix [/usr/local/] * Checking version of /usr/bin/blender... Found v.2.69.0 * Found Blender in your PATH (/usr/bin/blender, v.2.69.0). Alright, using it. * Checking version of Python within Blender /usr/bin/blender... Found v.3.4.3 * Blender and Morse are using Python 3.4.3. Alright.
rospy
is correctly setup. Open up a terminal. Type python3
and enter. Now try import rospy
. If you didn’t get any errors. You’re a rare gem on this planet.Now assuming you got everything correct, let’s move on to the next part. Running Morse. Let’s write a script for a simulation. This simulation be located inside a classroom and will have a robot, and the robot will have a camera and a laser. Pretty cool huh!
mkdir morse_tut && cd morse_tut
morse_tut_scene.py
in the newly created directory.from morse.builder import * atrv = ATRV() #the robot atrv.translate(x=2.5, y=3.2, z=0.0) #starting location # An odometry sensor to get odometry information odometry = Odometry() atrv.append(odometry) odometry.add_interface('ros', topic="/odom",frame_id="odom", child_frame_id="base_link") # Allows to control the robot with the keyboard keyboard = Keyboard() atrv.append(keyboard) #camera 10Hz, 320x240 image cam_frequency = 10 camera = VideoCamera() camera.translate(x = 0.7, z= 0.5) camera.rotate(y = -0.0) camera.properties(cam_width=320,cam_height=240,cam_focal=6.,cam_near=0.1,cam_far=500) camera.frequency(cam_frequency) atrv.append(camera) camera.add_interface('ros',topic='/camera') #laser 10Hz, 180 degrees wide with a 180 points scan = Hokuyo() scan.translate(x=0.275, z=0.252) atrv.append(scan) scan.properties(Visible_arc = True,laser_range = 30.0,resolution = 1,scan_window = 180.0) scan.frequency(10) scan.create_laser_arc() scan.add_interface('ros', topic='/scan',frame_id="laser", child_frame_id="base_link") #motion controller motion = MotionXYW() atrv.append(motion) motion.add_interface('ros', topic='/cmd_vel') # Set the environment env = Environment('indoors-1/indoor-1')
morse_tut
and run morse run morse_tut_scene.py
/home/user/catkin_ws/devel/lib/python2.7/dist-packages:/opt/ros/indigo/lib/python2.7/dist-packages:/usr/lib/python2.7/dist-packages:/usr/local/lib/python3/dist-packages:/home/user/ros/workspace/devel/lib/python2.7/dist-packages:/opt/ros/indigo/lib/python3/dist-packages
Now as we have Morse working, let’s try doing something cool with ROS. We will attempt sending out a warning if the robot is too close to an obstacle.
obstacle_check.py
and save it in morse_tut/
#!/usr/bin/env python import rospy from sensor_msgs.msg import LaserScan from nav_msgs.msg import Odometry import numpy as np # get the laser messages def callback_laser(msg): global curr_pose laser_raw = msg.ranges laser_float = [float(r) for r in laser_raw] if np.min(laser_float)<0.5: print "I bumped at (X:%.2f Y:%.2f). Please Reverse."%(curr_pose[0],curr_pose[1]) # get the odometry messages def callback_odom(msg): global curr_pose,curr_ori pose = msg.pose.pose # has position and orientation curr_pose = [float(pose.position.x),float(pose.position.y),float(pose.position.z)] curr_ori = [float(pose.orientation.x),float(pose.orientation.y),float(pose.orientation.z),float(pose.orientation.w)] if __name__=='__main__': rospy.init_node("obstacle_check_node") rospy.Subscriber('/scan', LaserScan, callback_laser) rospy.Subscriber('/odom', Odometry, callback_odom) rospy.spin() # this will block untill you hit Ctrl+C
roscore
and entercd morse_tut/
then, morse run morse_tut_scene.py
cd morse_tut/
then, python obstacle_check.py
user@pc:~/morse_tut$ python obstacle_check.py I bumped at (X:-2.78 Y:2.85). Please Reverse. I bumped at (X:-2.88 Y:2.85). Please Reverse. I bumped at (X:-2.95 Y:2.85). Please Reverse. I bumped at (X:-2.96 Y:2.85). Please Reverse. I bumped at (X:-2.94 Y:2.85). Please Reverse.
Versions Ubuntu: 14.04 Morse: 1.4 Ros: Indigo Python: 2.7 and 3.4 Introduction Before diving in to the “guide”, let me explain a hypothetical scenario. Say you want to install ROS in your computer. Should be easy as a pie right? sudo apt-get install ros-indigo-desktop-full should do the trick. Now as...
G’day, Now some advance stuff after touching the surface of ROS. But it should feel good to have something up and running. Now let’s try to run a simulated robot with ROS. Sounds pretty cool, doesn’t it? We will be using the following components in our simulation. Morse – 1.3...
Hi there, This tutorial is about using ROS. ROS stands for Robotics Operating System, which is pretty much self-explanatory. ROS is widely used to provide a platform for robots to function. And the ROS official website itself provide a gold-mine of tutorials and information. So I would not give a...