extending player/stage/gazebo towards cognitive robots ...gerkey/papers/icra07.pdffig. 1. cognitive...

9
Extending Player/Stage/Gazebo towards Cognitive Robots Acting in Ubiquitous Sensor-equipped Environments Radu Bogdan Rusu, Alexis Maldonado, Michael Beetz Intelligent Autonomous Systems, Technische Universit¨ at M¨ unchen {rusu, maldonad, beetz}@cs.tum.edu Brian Gerkey Artificial Intelligence Center SRI, International [email protected] Abstract— Standardized middleware for autonomous robot control has proven itself to enable faster deployment of robots, to make robot control code more interchangeable, and experi- ments easier to replicate. Unfortunately, the support provided by current middleware is in most cases limited to what current robots do: navigation. However, as we tackle more ambitious service robot applications more comprehensive middleware support is needed. We increasingly need the middleware to support ubiquitous sensing infrastructures, robot manipulation tasks, and cognitive capabilities. In this paper we describe and discuss current extensions of the Player/Stage/Gazebo (P/S/G) middleware, one of the most widespread used robot middleware, of which we are active developers, that satisfy these requirements. I. I NTRODUCTION Up to a decade ago the robotics community was focussing mainly on robots acting autonomously in real and unmodified environments. The goal was to enable the robots to do, like humans and animals do, all sensing, deliberation, and action selection on board. With the establishment of new research fields including ubiquitous computing, alternative paths to competent robotic agency have become very plausible and even more promising. In ubiquitous computing, sensors, effectors, and com- puting devices are distributed and embedded invisibly into the objects of everyday life. They connect automatically to each others, exchange information, and pass commands to connected components. In sensor-equipped environments we have cupboards that “know” what’s inside of them because objects are tagged with RFID tags and the boards equipped with RFID tag readers. Or, we have people who are instrumented with inertial measurement units at their joints providing sensor data about the orientations of the limbs. If we think about the future of service robotics it seems likely that service robots will be competent and versatile agents in sensor- and effector-equipped operating environ- ments rather than autonomous and insular entities. In ubiquitous robotics, a typical setting is the following one. A service robot establishes a connection to the ubiq- uitous computing, sensing, and actuation infrastructure and makes itself a part of this infrastructure. Having established the connection, the robot then perceives what is inside a cupboard in the same way as it perceives what is in its hand: by simply retrieving the respective sensor data and interpreting it — although it is not physically connected to the sensor. To enable and support such seamless integration we pro- pose a common middleware infrastructure for autonomous robots and ubiquitous computing environments [1], [2]. Our running example will be a mobile kitchen robot (see Figure 1) acquiring the skills for setting a table through imitation learning, where a sensor-equipped kitchen observes people setting the table. The robot learns activity models from these observations, and uses the acquired action models as resources in order to learn high performance action routines. This is an interesting and challenging problem for cognitive robotics because it involves complex manipula- tion tasks, the acquisition and use of 3D object maps, the learning of complex action models and high-performance action routines, and the integration of an ubiquitous sensing infrastructure into robotic control — aspects that are beyond the scope of current autonomous robot control systems. Fig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions to the Player/Stage/Gazebo software library that include drivers and interfaces of an ubiquitous sensing infrastructure, (2) a report on an extended and comprehensive experiment using this infrastructure for recording kitchen activities of people and learning action models, (3) a sketch of ongoing work to integrate higher level support for complex manipulation and model acquisition tasks, and (4) our plans on developing and integrating cognitive mechanisms into P/S/G. Taken together, these components give a comprehensive overview of the current state and the future plans of a key development thread of P/S/G.

Upload: others

Post on 04-Aug-2020

1 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

Extending Player/Stage/Gazebo towardsCognitive Robots Acting in Ubiquitous Sensor-equipped Environments

Radu Bogdan Rusu, Alexis Maldonado, Michael BeetzIntelligent Autonomous Systems, Technische Universitat Munchen

{rusu, maldonad, beetz }@cs.tum.edu

Brian GerkeyArtificial Intelligence Center SRI, International

[email protected]

Abstract— Standardized middleware for autonomous robotcontrol has proven itself to enable faster deployment of robots,to make robot control code more interchangeable, and experi-ments easier to replicate. Unfortunately, the support providedby current middleware is in most cases limited to what currentrobots do: navigation. However, as we tackle more ambitiousservice robot applications more comprehensive middlewaresupport is needed. We increasingly need the middleware tosupport ubiquitous sensing infrastructures, robot manipulationtasks, and cognitive capabilities. In this paper we describeand discuss current extensions of the Player/Stage/Gazebo(P/S/G) middleware, one of the most widespread used robotmiddleware, of which we are active developers, that satisfythese requirements.

I. I NTRODUCTION

Up to a decade ago the robotics community was focussingmainly on robots acting autonomously in real and unmodifiedenvironments. The goal was to enable the robots to do, likehumans and animals do, all sensing, deliberation, and actionselection on board. With the establishment of new researchfields including ubiquitous computing, alternative paths tocompetent robotic agency have become very plausible andeven more promising.

In ubiquitous computing, sensors, effectors, and com-puting devices are distributed and embedded invisibly intothe objects of everyday life. They connect automaticallyto each others, exchange information, and pass commandsto connected components. In sensor-equipped environmentswe have cupboards that “know” what’s inside of thembecause objects are tagged with RFID tags and the boardsequipped with RFID tag readers. Or, we have people who areinstrumented with inertial measurement units at their jointsproviding sensor data about the orientations of the limbs.

If we think about the future of service robotics it seemslikely that service robots will be competent and versatileagents in sensor- and effector-equipped operating environ-ments rather than autonomous and insular entities.

In ubiquitous robotics, a typical setting is the followingone. A service robot establishes a connection to the ubiq-uitous computing, sensing, and actuation infrastructure andmakes itself a part of this infrastructure. Having establishedthe connection, the robot then perceives what is inside acupboard in the same way as it perceives what is in itshand: by simply retrieving the respective sensor data andinterpreting it — although it is not physically connected tothe sensor.

To enable and support such seamless integration we pro-pose a common middleware infrastructure for autonomousrobots and ubiquitous computing environments [1], [2].

Our running example will be a mobile kitchen robot (seeFigure 1) acquiring the skills for setting a table throughimitation learning, where a sensor-equipped kitchen observespeople setting the table. The robot learns activity modelsfrom these observations, and uses the acquired action modelsas resources in order to learn high performance actionroutines. This is an interesting and challenging problem forcognitive robotics because it involves complex manipula-tion tasks, the acquisition and use of 3D object maps, thelearning of complex action models and high-performanceaction routines, and the integration of an ubiquitous sensinginfrastructure into robotic control — aspects that are beyondthe scope of current autonomous robot control systems.

Fig. 1. Cognitive Household Robotic Assistant

This paper gives (1) an overview of recent additions tothe Player/Stage/Gazebo software library that include driversand interfaces of an ubiquitous sensing infrastructure, (2) areport on an extended and comprehensive experiment usingthis infrastructure for recording kitchen activities of peopleand learning action models, (3) a sketch of ongoing work tointegrate higher level support for complex manipulation andmodel acquisition tasks, and (4) our plans on developing andintegrating cognitive mechanisms into P/S/G. Taken together,these components give a comprehensive overview of thecurrent state and the future plans of a key development threadof P/S/G.

Page 2: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

In more detail, the main contributions of this paper are thefollowing ones:

1) Extensions for interfacing ubiquitous sensing infras-tructure include a coherently designed library of in-terfaces to a variety of sensing and computing deviceswith incompatible native software interfaces, additionallogging and synchronization mechanisms, and mech-anisms for querying multiple sensors and combiningthe resulting data.

2) Extensions for the integration of robotic manipulation.The upcoming need for more sophisticated manipu-lation capabilities constitutes another interesting chal-lenge for robotic middleware. Robotic manipulation ina kitchen scenario requires reach planning in sophis-ticated 3D maps that are generated on the fly duringa reach motion. It also requires the recognition andsometimes even the identification of objects, measuringtheir form accurately in order to propose adequate grippositions.

3) Extensions for enabling cognitive processing in P/S/Gwill enable Player to realize self-calibrating sensor-equipped environments, to effectively support the sim-plification of sensing tasks by exploiting contextual in-formation, and to realize higher-level perceptual taskssuch as activity recognition as it is needed to realizecognitive robots in human environments.

In the remainder of the paper we proceed as follows.Section II provides an overview of our system. SectionIII describes our architectural and cognitive layer. SectionIV presents our Player/Stage/Gazebo extensions in greaterdetail. Section V describes our application scenario and someexperimental results. Section VI presents related work andfinally, in section VII we draw the conclusions.

II. A PPLICATION SCENARIO AND OVERVIEW

Let us now (Section II-A) look at a specific applicationscenario that we will use to motivate our P/S/G extensionsand derive requirements for these extensions in Section II-B.

A. Kitchen Scenario

As the example application scenario that we consider forthe extension of P/S/G, we take an autonomous mobile robotequipped with two arms with grippers acting in a sensor-equipped kitchen environment.

The robot is a RWI B21 robot (see figure 5) equipped witha stereo CCD system and laser rangefinders as its primarysensors. It also has two AMTEC powercube arms with simplegrippers. The robot’s task will be to set the kitchen table bygetting plates and glasses out of the cupboard and puttingthem on the table.

The sensor-equipped kitchen environment consists ofRFID tag readers placed in the cupboards for sensing theidentities of the objects placed there. The cupboards alsohave contact sensors that sense whether the cupboard isopen or closed. A variety of wireless sensor nodes equippedwith accelerometers and/or ball motion sensors are placed on

objects or other items in the environment. Several small, non-intrusive laser range sensors are placed in the environmentto track the motions of the people acting there.

Fig. 2. A general overview of the AwareKitchen architecture

The kitchen table is equipped with a suite of capacitysensors that essentially report the capacitance of differentareas on the table, when an object is placed there. In addition,seven CCD cameras are mounted such that they coverthe whole environment. Finally, machines and tools in thekitchen are also equipped with sensors. The coffee machineis equipped with sensors that tell the parts that are open andclosed, whether it is filled, and whether it is switched on.Also, we have a knife equipped with a force/torque sensorthat enables the system to perceive the classes of objects thatare cut based on their characteristic cutting pressure profiles.

Small ubiquitous devices offer the possibility to instrumentpeople acting in the environment with additional sensors. Inour case, we have built a glove equipped with a RFID tagreader (see Figure 7) that enables us to identify the objectsthat are manipulated by the person who wears it. In addition,the person is equipped with tiny inertial measurement units(XSens MTx) who provide us with detailed informationabout the person’s limb motions.

It is characteristic for sensor-equipped environments tohave sensors which provide redundant information, thusevidencing that some state variables are provided by multiplesensors. Another aspect is that the sensors only providepartial information about the state we are interested in. Forexample, the RFID tag reader in the glove senses that anobject with a certain id is close to the glove but it cannottell us whether the object is in the hand, the state we might

Page 3: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

be interested in.An important property of the sensing infrastructure of

the kitchen is that the sensors are wirelessly connected toother small ubiquitous devices (like Gumstix) and personalcomputers that perform state estimation and dataminingtasks. This way, activity data can be collected and the activitymodels are acquired distributedly.

Fig. 3. Images from the Awarekitchen experiment

As our application task we consider the following scenariothat we want to support with our extensions to the P/S/Gmiddleware. Several people are setting the table for differentnumbers of guests. The sensor-equipped kitchen observes thesetting and learns abstract models for the setting activity.These abstract models are then transferred to the servicerobot which uses the models to imitate the coarse tablesetting activity. It then uses the learned activity model asthe starting point for behavior optimization.

B. Requirements for P/S/G Extensions

In order to support future application scenarios as the onedescribed in the previous section a middleware infrastructureshould successfully address the following requirements.

To support ubiquitous sensor-equipped environments, themiddleware has to address interoperability protocols, makingcommunication between heterogeneous sensors and actuatorspossible, and then leave room for fusion, processing andreasoning extensions on top.

As an example, it should be possible to easily combinean off-the-shelf navigation system (motors, encoders andcontroller) with a range finder sensor (sonar, laser, etc) tobuild a mobile platform, without almost any programmingefforts, and after that, use the very same platform to buildlocalization and mapping algorithms on top, thus making themobile platformcognitiveof its location.

From an architectural point of view, the system must beas flexible and as powerful as possible. For infrastructure tobecome widely adopted by the community, it must imposefew, if any, constraints on how the system can be used.

Specifically, we require independence with respect to pro-gramming language, control paradigm, computing platform,sensor/actuator hardware, and location within a network.In other words, a researcher should be able to: write acontrol program in any programming language, structurethe program in the best way for the application at hand,run the program on any computer (especially low-powerembedded systems), make no changes to the program afterintegrating new hardware, and remotely access the programover a network. Though not a strict requirement, we alsoaim to maximize the modularity of our architecture, so that

researchers can pick and choose the specific components thatthey find useful, without using the entire system.

We also require a realistic, sensor-based simulation. Simu-lation is a key capability for ubiquitous computing infrastruc-ture. The main benefits to the user of using a simulation overreal hardware are convenience and cost: simulated devicesare usually easy to use, their batteries need not run out,and they are much cheaper than real devices. In addition,simulation allows the user to explore system configurationsand scales that are not physically realizable because thenecessary hardware is not available. The simulation mustpresent the user with the same interface as the real devices, sothat moving an experiment between simulation and hardwareis seamless, requiring no changes to the code. Though theymay seem lofty, these goals are in fact achievable, as weexplain below.

As we envision technical cognitive robotic systems whowill become more and more decentralized, using ubiquitouscomputing devices that communicate and exchange infor-mation between each other, one of our goals is to com-bine research results from both the robotics and ubiquitouscomputing research communities, thus bringing them closertogether.

III. P/S/G ARCHITECTURE

The Player/Stage/Gazebo (P/S/G) project produces toolsfor rapid development of robot control code. In the P/S/Gsoftware suite, Player provides a simple and flexible interfacefor communicating with, and controlling different physicallydistributed sensors and actuators. Stage and Gazebo areare 2D and 3D simulators for multiple robots that includephysical simulations.

Fig. 4. A general overview of the Player/Stage/Gazebo architecture

Player provides a simple and flexible interface for robotcontrol by realizing powerful classes of interface abstractionsfor interacting with robot hardware, in particular sensorsand effectors. These abstractions enable the programmer touse devices with similar functionality identically from thecode point of view, thus increasing the transferability of thecode. In addition, an enhancedclient/server modelfeaturingautodiscovery mechanisms as well as permitting servers andclients to communicate between them in a heterogeneousnetwork, enables programmers to code their clients from alarge variety of programming languages. Due to the standardsthat P/S/G imposes on its architectural and transport layer,several client libraries for programming languages such as:

Page 4: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

C, C++, Java, Lisp, Python, Ada, Tcl, Ruby, Octave, Matlab,and Scheme, are already available [3].

An important aspect of the P/S/G middleware is that it isdeveloped as a Free Software infrastructure for robots andembedded sensor systems that improves robotics researchpractice and accelerates development by handling commontasks and provides a standard development platform. Bycollaborating on a common system, we share the engineer-ing burden and create a means for objectively evaluatingpublished work. If you and I use a common developmentplatform, then you can send me your code and I can replicateyour experiments in my lab.

The core of the project is Player itself, which functions asthe OS for a sensor-actuator system, providing an abstractionlayer that decouples the user’s program from the details ofspecific hardware (see Figure 5).

Fig. 5. An example of the Player↔ client architecture

Player specifies a set ofinterfaces, each of which definesthe syntax and semantics for the allowable interactions witha particular class of sensor or actuator. Common interfacesinclude laser and ptz, which respectively provide access toscanning laser range-finders and pan-tilt-zoom cameras. Ahardware-specificdriver does the work of directly controllinga device and mapping its capabilities onto the correspondinginterface. Just as a program that uses an OS’s standardmouseinterface will work with any mouse, a program that usesPlayer’s standardlaser interface will work with any laser,may it be a SICK LMS200 range-finder or a Hokuyo URG-04LX one.

The 2-D simulator Stage and the 3-D simulator Gazebo(see Figure??) also use a set of drivers to map theirsimulated devices onto the standard Player interfaces. Thusthe interface that is presented to the user remains unchangedfrom simulation to hardware, and back. For example, aprogram that drives a simulated laser-equipped robot inGazebo will also drive a real laser-equipped robot, with nochanges to the control code. Programs are often developedand debugged first in simulation, then transitioned to hard-ware for deployment.

In addition to providing access to (physical or simulated)hardware, Player drivers can implement sophisticated algo-

rithms that use other drivers as sources and sinks for data.For example, thelasercspacedriver reads range data froma laser device and convolves that data with the shape of arobot’s body to produce the configuration-space boundary.That is, it shortens the range of each laser scan such thatthe resultant scan delimits the obstacle-free portion of therobot’s configuration space [4]. Thelasercspacedriver’soutput conforms to thelaser interface, which makes it easyto use. Other examples of algorithm drivers include adaptiveMonte Carlo localization [5]; laser-stabilized odometry [6];and Vector Field Histogram navigation [7]. By incorporatingwell-understood algorithms into our infrastructure, we elim-inate the need for users to individually reimplement them.

Our architectural layer can be broken down into severalparts:

• Low-level connections to the hardware platforms• Sensor fusion and processing• Reasoning algorithms

Fig. 6. Graph of Player drivers and their appropriate interfaces

One can think of the Player driver system as a graph(see Figure 6), where nodes represent the drivers whichinteract via well-defined interfaces (edges). Because it isembodied, this graph is grounded in the robot’s (physicalor simulated) devices. That is, certainleaf drivers of thegraph are connected to sensors and actuators.Internal driversthat implement algorithms (e.g., localization) are connectedonly to other drivers. Because the interfaces are well-defined,drivers are separable in that one can be written withoutknowledge of the internal workings of another. If my al-gorithm requires data from a laser range-finder, then thedriver that implements my algorithm will have take inputover a laser edge from another driver; I don’t care howthat data gets produced, just that it is standardlaser data.A wide variety of control systems can be constructed byappropriately parameterizing and connecting drivers. Thecontrol system is also accessible from the outside; an externalprogram (e.g., a client) can connect to any driver, via thesame standard interfaces. Thus the system is, to a limitedextent, reconfigurable at run-time. Figure 2 presents a partof our Awarekitchen’s architectural layer. The arrows depictthe connections between the actual hardware platforms and

Page 5: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

their appropriate software interfaces. A hardware device isaccessible via one or more Player drivers, through the useof standardized, pre-defined interfaces.

IV. EXTENDING P/S/G

The following sections describe the extensions that we arecurrently working on implementing into P/S/G, as part of ourongoing research. Some of them are already available in ourCVS repository on SourceForge, and the rest will be madeavailable soon, together with the release of Player 3.0.

A. Ubiquitous Sensing Infrastructure

Extending P/S/G towards ubiquitous sensing includes acumbersome development effort providing drivers for sensorssuch as heterogeneous Wireless Sensor Networks, RFIDtechnologies and Inertial Measurement Units, and manymore. This is a time consuming task because companiesare starting selling potentially useful new sensors on a dailybasis. Typically, these sensors have incompatible interfacesand sometimes the interfaces are even buried in singlespecific applications that the sensors are made for.

Fig. 7. Wireless Sensor Networks and RFID technologies in Player

A series of new hardware platforms are going to besupported with the upcoming release of Player 2.1. We haveadded support for:

• Wireless Sensor Networks- with a wide variety ofdifferent sensor nodes, ranging from the RCores andParticles from TeCO/Particle Computers to the Mica2and Mica2Dots from Crossbow;

• RFID technologies- several readers such as the InsideM/R300, the Skyetek M1 and the Skyetek M1-mini arenow supported;

• Inertial Measurement Units - supporting the XSensMT9 as well as the XSens MTx, which provides drift-free 3D orientation and kinematic data.

Besides these, we implemented a number of virtual driverswhich take care of sensor calibration, data fusion, syn-chronization and logging. Furthermore, automatic featureextraction plugins are now available (see [1] for more details)and drivers for feature boosting as well as learning SVMmodels are underway.

Besides driver development the integration of ubiquitoussensing and computing infrastructure also yield interestingchallenges: the incorporation of new sensing infrastructureduring operation and the active querying of sensor networksfor specific information as it is done, for instance, in TinyDB[8].

B. Supporting robotic manipulation

Most middlewares for robots provide little support formanipulation tasks. As we go for cognitive/service robotsthat are more sofisticated and have to solve more complicatedtasks, manipulation is essential. Therefore a key direction inextending P/S/G is to provide the adecuate infrastructure.

For example, our robot (see section II-A) has been modi-fied with two AMTEC Powercube arms with six degrees offreedom each. They are very recent state-of-the-art manipu-lators and support a variety of commands that make controlvery flexible. Each joint has its own integrated controller thatsupports position, velocity, and current commands. Thereis also support for synchronized commands to all jointsof one manipulator, and synchronized sampling of positiondata. In order to make use of these advanced capabilities,we have created a P/S/G middleware infrastructure for themanipulators. This middleware components provide toolsfor acquiring and using 3-D obstacle maps, and efficientmanipulator control. We discuss these issues by looking at3-D mapping, trajectory planning in 3-D space, and finallythe safe execution of such trajectories.

1) 3-D Mapping: In order to be able to perform roboticmanipulation in a complex environment, the system needs afine-grained 3d polygonal map, updated preferably as oftenas possible.

3D mapping in the context of mobile robotics is not anew subject, and several researchers have already presenteda number of contributions to this field [9], [10], [11]).However, there is no public implementation available of theabove mentioned algorithms, so the regular user still has togo through a cumbersome process of developing its ownroutines before attempting to go any further (eg. towards 3dobject maps). Therefore, we are proposing an open-sourceimplementation of a probabilistic algorithm for developing3d polygonal maps, useful in indoor scenarios. We buildupon the assumption that we are dealing with structured,indoor environments, where most of the surfaces can beapproximated via planar/polygonal surfaces.

Our algorithm needs an unorganized 3d point cloud asinput, preferably from an indoor structured environment, andprovides a 3d polygonal description of it as output. The usercan decide if the point cloud should be divided into 3d gridcells or not, decision which can greatly affect the speed ofthe plane fitting algorithm. However, we have found thatfor small environments, applying a brute force plane fittingmethod works just as well.In order to separate the 3d space into planes and lateron, polygons, we use a RANSAC implementation followedby a least-squares method for finding out the parameters ofthe fitted plane. Once the plane has been found, the inliersare projected onto it, and then a density-based clustering

Page 6: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

Fig. 8. Preliminary results obtained with the polymap driver (left: corrected3D cloud point, right: polygonal interpretation of it)

method is applied [12]. After that, for each cluster found, aDelunay triangulation followed by an outline shape detectionalgorithm is performed. Finally, polygonal smoothing isapplied.

One usage example is demonstrated in Figure 6. As shownthere, thelaserptzcloud driver takes a laser 2d scan froma laser interface and the pan-tilt angles of a PTZ unitvia a ptz interface, computes the corrected 3d coordinatesof each point in space, and outputs a 3d point cloud viathe pointcloud3d interface. Thepolymap driver uses theresulted 3d point cloud, and, via a few configuration requests,computes the best N planes that contain X (given) inliers, fitsthe inliers to the planes, extracts the appropriate clusters andtries to find polygonal outlines (see Figure 8).

2) 3-D Trajectory planning:For reaching and manipula-tion tasks with the robotic arms, knowing the final positionsfor the joints is only half the solution: It is also important tofind the best way to move the robotic arm there, for examplewithout colliding with obstacles. A trajectory planner isneeded. Our proposal is to use the Motion Strategy Library(MSL) (quote), that includes a variety of motion planners.Of special interest are the RRT planners included.

The MSL needs a geometrical model of the environment inorder to operate. We plan extract a geometrical representationof the environment around the robot using 3-D Mapping, asdescribed in the next section.

C. Execution of the planned trajectories

Once we are able to control the movement of every joint,the next step is finding the correct angles for each joint,so that the end-effector of the arm (a simple gripper inour case) reaches a desired point in space with a desiredorientation. This is known as the inverse kinematics problem.We solve this in a very general way by using ROBOOP(quote), an LGPL software library that implements stan-dard solutions for direct and inverse kinematics. We aredeveloping a Player driver that has a LIMB interface forinputting the desired position and pose, and controls anACTARRAY interface connected to a robotic manipulator.This driver reads the description from the arm expressedwith the Denavit-Hartenberg convention, the standard wayof describing kinematic chains (manipulators). In this way

the driver can be used for any robot manipulator that has adriver in P/S/G.

One of the goals of our project is to create models fromactions using information from the arms. On this context itis very important to have precise data regarding the state ofall the joints in the arm, and the data for all joints shouldbe sampled synchronized and with a constant framerate. Tosolve this problem, the Powercube driver uses broadcastcommands on the CAN bus to instruct all modules torecord their positions at the same time, and the data isthen recovered serially from all of them. To have a veryconstant framerate, the driver includes code to order thekernel scheduler to treat the Player server as a (soft) realtime process, and it also takes advantage of the recentimprovements to POSIX timers in the Linux kernel, calledthe High-Resolution-Timers infrastructure. In this way, thecontrol loop of the arm runs with deviations of less than10uS in the cycle time on modern computers without havingto run the arm controller in kernel-space.

Since the manipulators are strong enough to hurt peopleor equipment around the robot, the driver also implementssecurity features like a watchdog, that will stop the arm ifthe Player server stops responding for more the 50mS.

It is useful to learn a model of the dynamics of the ma-nipulator in order to improve its movements. The whole armcan be conceptualized as a kinematic chain made up rigidsections and joints between them. The kinematic responseof each joint depends on the torque applied by the motorof the joint and the positions, velocities and accelerationsof all joints in the arm, which makes the feature space forlearning the model very large. To succesfully learn a modelfor each joint, we apply an algorithm that deals well withthe ’curse-of-dimensionality’ (quote). The algorithm is calledLinear Weighted Progression Regression (LWPR). (quote).

People and robots have to do joint action -¿ Have reachingand manipulation that is compatible with human reaching andgrasping. (Or understandable/expectable by humans).

Many manipulation tasks are repetitive, so you can acquireskills through experience and they can be adapted to newvariations. -¿ Then if we think about it this way, learningthe dynamics is the right way.

D. Extensions for Cognitive Processing

It is certainly an issue whether or not cognitive capabilitiesshould be incorporated into a middleware tool such as P/S/G.The pros are that many perceptual and sensing tasks canbe drastically simplified using contextual information. Onecon is that the provision of cognitive mechanisms might beviewed as a methodological commitment that we might notwant to make at the middleware layer. We believe that theadvantages outweigh the disadvantages.

We can take advantage of cognitive capabilities in themiddleware layer to ease the interpretation of sensor datafor safety and collision avoidance. For example, when therobotic arm is moving in what it thinks is free space, and itsenses a small force applied on it, it should stop immediately,because it has just crashed against something. But when the

Page 7: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

arm is picking up an object, a sensed force is expected and itis part of the normal manipulation action. The threshold forthe emergency stop of the arm based on sensed forces canbe set accordingly to the context and the intended action.

On the other hand, in order to facilitate research in cog-nitive areas, the middleware has to support certain advancedfeatures. One example is applying learning for the armmanipulator. It requires a very tight integration of the low-level and high level control processes. The sensor data inparticular must be synchronized and sampled uniforminglyand the middleware must support this. This has been takeninto account when designing the Player driver for our robotmanipulators, as explained in section IV-C.

The different parts of the middleware can be combined tocreate powerful systems. For example, if we want to pickup a cereal box with the robotic arm we can use the 3-DMapping driver to obtain a map of the object and find outits position, while using an RFID reader to detect its identity.And with the object identified, the grasp planner can searchfor its detailed stored model, and select the best approachfor grasping.

The cognitive processing layer should not be somethingisolated on top of the middleware. On the contrary, havingit embedded into the the middleware allows for more morepowerful and flexible systems to be developed.

E. Usage examples

The usage of the above described extensions is prettystraightforward, and requires little programming skills andonly on the client side (for usage). All the parameters of adriver, may it be a low-level hardware driver or a higher levelvirtual one, are set via the Player configuration file initially,and later on via client configuration requests. The followingexample depicts the usage of our automatic accelerationfeature extraction driver, for nodes in a Wireless SensorNetwork.

driver (name ”accelfeatures”provides [”features:0” ”wsn:1”]requires [”wsn:0”]window size 16queuesize 10000overlapping 50featurelist [”wavelet coeff” ”ica”]waveletparams [”daubechies” 20]

)... ↓ ...

... ↓ ...driver (

name ”accelfeatures”provides [”features:1” ”wsn:2”]requires [”wsn:1”]window size 16queuesize 10000overlapping 50featurelist [”energy” ”rms” 11

”skewness” ”magnitude” 15 18])

In this case, the accelfeatures driver will spawn two dif-ferent threads, using the output of the first as the input of thesecond. Therefore, the first thread will receive accelerationdata via thewsn:0 interface, calculate wavelet coefficientsusing Daubechies 20 and perform Independent ComponentAnalysis (ICA) in parallel, and finally pack the resultedvalues in thewsn:1 interface. The second thread will takethe results fromwsn:1 as input, and will compute standardfeatures such as energy, RMS, magnitude and so on and willprovide the results to the user via thewsn:2 and features:1interfaces. The calculated features will be used later on to

learn SVM (Support Vector Machines) models (see [1] formore information), and build a library of motion blueprints.

V. EXPERIMENTAL RESULTS

Our experiment consisted in having a number of peopleinstrumented with tiny Inertial Measurement Units as well aswith a RFID-enabled glove, setting up the table, while thesystem observes and gathers sensor data.

The environment was instrumented with a large numberof sensors. Seven video cameras were positioned so that allpossible angles are covered, and three small, non-intrusive,laser sensors have been carefully placed in the environmentfor tracking people movements. Two long-range RFID read-ers were placed in the cupboards, and several kitchen objectshave been equipped with RFID tags. Additionally, four moresmaller RFID readers together with eight capacitive sensorswere placed under a kitchen table for detecting where andwhat type of objects were on the table.

On each cupboard door, we placed magnetic sensors inorder to find out if the door is open or closed. Light andtemperature sensors together with Wireless Sensor Networknodes have been scattered throughout the AwareKitchen instrategic places. Finally, we instrumented a knife with aforce/torque sensor for experiments regarding various pro-files for cutting different types of food,as well as a coffeemachine with...

This huge heterogeneous hardware device pool worksunder the same framework in our infrastructure. All sensordata is synchronized and logged from different places in thenetwork.

As mentioned above, one of our experiments includedsetting up the table for two persons. Data from the inertialmeasurement sensors, RFID readers, wireless sensor nodes,capacitive sensors, laser sensors as well as video cameraswas recorded.

...The robot assistant sits and observes. The environmentimproves its ADL models by fusing new observations withits current internal model. When the a model probability ofbeing good raises above a certain threshold, the robot picksup and starts using it....

As explained in Section IV, our manipulation routinesrely on a precise 3D polygonal models of the environment.We are currently using several fixed laser scanners in theenvironment, together with other laser scanners mounted onpan-tilt units, as well as stereo cameras on the robot.

After the acquisition of the 3d point cloud and the com-putation of the associated polygons, the model is being fedup to our RTT-planner. An example of an intermediate 3dpolygonal map automatically generated by our system isshow in Figure 8.

Each polygon is described with a different color. Futurework will include optimizations of the algorithms used, aswell as research on fitting textures from camera images ontothe polygonal map, all of which will be made available asfree software through the P/S/G project.

Before attempting to use our robot assistant in the realworld, we go through several stages of fine-grained simu-

Page 8: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

lation of our plans and controllers. To perform an accurate3D simulation, we make use of the Gazebo simulator, underwhich we created an environment similar to the real one(see Figure 9). By introducing error models in our sensorydata and employing probabilistic techniques in the simulator,we can achieve similar results in the real world, withoutchanging our programming infrastructure or algorithms.

Fig. 9. A Gazebo simulation of the Awarekitchen

VI. RELATED WORK

Related work can be categorized on several dimensions.On the middleware side, there are several other software

packages positioned closely to Player/Stage/Gazebo. Dueto space constraints, a comparison between them will notbe made here. Instead, we will give a list of publicationsthat cover a lot of pros and cons of each project from anarchitectural point of view [13], [14], [2].

A very important aspect for a robotic middleware is thatit has to keep up with the rapid advancements in the field,and thus be as flexible as possible. During the last 8 years,Player/Stage has been consistently and continuously evolv-ing. According to [3], over 50 different research laboratoriesand institutions all around the world are currently involved inthe active development of P/S/G, and even more are using it.Overall, we believe that one of the key features of a projectof this size should be its ease of maintenance (achieved inP/S/G’s case through simplicity and transparency of the de-veloper API), because the pool of researchers and developerschanges rapidly [13].

Research projects in the ubiquitous community have cre-ated fully instrumented sensor-equipped environments, oneof the leading initiatives in this field being MIT’s Placelab[15]. There are other efforts underway, but they do notcover complete environments (entire apartments), but rathermore limited scenarios. In comparison to the PlaceLab, wecomprise a more comprehensive sensor suite in our Awarek-itchen, mostly because we are interested in transferring skillsfrom humans to robots through developmental learning, thuswe need more complete action models.

With respect to other related work regarding our P/S/Gextensions, we have referenced the appropriate articles inour technical section.

At the best of our knowledge, the integration of suchadvanced techniques in such a comprehensive way has notbeen performed in other comparable initiatives.

VII. C ONCLUSION AND FUTURE WORK

For the conclusion: Ubiquituous sensing infranstructureprovides better sensing for context. Normally in autonomousrobotics you look at everything as a Partially ObservableState, because you asume the robot always has incompleteinformation. with ubiq sensing this changes, because weget now all this extra information about the state of theworld, and it changes the control of the autonomous robots.Because the information about the relevants parts of theenvironment is much more complete. Example: in a sensorequip environment there is less need for searching.

For the conclusion: the distinction between middlewaresgets blurred because they are normally just for communica-tion, and we are using it for processesing, also. It is morethan a simple middleware.

VIII. A CKNOWLEDGEMENTS

This work has been jointly conducted by the IntelligentAutonomous Systems group at the Techische UniversitatMunchen and the Artificial Intelligence Center at SRI, In-ternational. This work is supported in part by the NationalScience Foundation under grant IIS-0638794.

We would like to thank the entire P/S/G community fortheir continuous effort in developing and maintaining freesoftware tools for robot and sensor applications.

REFERENCES

[1] M. Kranz, R. B. Rusu, A. Maldonado, M. Beetz, and A. Schmidt, “APlayer/Stage System for Context-Aware Intelligent Environments,” inProceedings of UbiSys’06, System Support for Ubiquitous ComputingWorkshop, at the 8th Annual Conference on Ubiquitous Computing(Ubicomp 2006), September 17-21 2006.

[2] B. Gerkey, R. T. Vaughan, and A. Howard, “The Player/Stage Project:Tools for Multi-Robot and Distributed Sensor Systems,” inIn Pro-ceedings of the 11th International Conference on Advanced Robotics(ICAR 2003), pages 317-323, June 2003.

[3] “Player/Stage/Gazebo: Free Software tools for robot and sensor appli-cations,” http://playerstage.sourceforge.net.

[4] J.-C. Latombe,Robot Motion Planning. Norwell, Massachusetts:Kluwer Academic Publishers, 1991.

[5] D. Fox, “KLD-sampling: Adaptive particle filters,” inProc. of Ad-vances in Neural Information Processing Systems (NIPS). MIT Press,2001.

[6] F. Lu and E. Milios, “Robot pose estimation in unknown environmentsby matching 2D range scans,”J. of Intelligent and Robotic Systems,vol. 18, no. 3, pp. 249–275, May 1997.

[7] I. Ulrich and J. Borenstein, “VFH+: Reliable obstacle for fast mobilerobots,” in Proc. of the IEEE Intl. Conf. on Robotics and Automation(ICRA), May 1998, pp. 1572–1577.

[8] S. R. Madden, J. M. Hellerstein, and W. Hong, “TinyDB: In-networkquery processing in TinyOS,” http://telegraph.cs.berkeley.edu/tinydb,September 2003.

[9] Y. Liu, R. Emery, D. Chakrabarti, W. Burgard, and S. Thrun, “UsingEM to learn 3D models with mobile robots,” inProceedings of theInternational Conference on Machine Learning (ICML), 2001.

[10] J. Weingarten, G. Gruener, and R. Siegwart, “A fast and robust 3d fea-ture extraction algorithm for structured environment reconstruction,” inProceedings of 11th International Conference on Advanced Robotics(ICAR), 2003.

[11] J. Weingarten, G. Gruner, and R. Siegwart, “Probabilistic plane fittingin 3d and an application to robotic mapping,” inProc. of the IEEEIntl. Conf. on Robotics and Automation (ICRA), 2004.

[12] S. J., E. M., K. H.-P., and X. X., “Density-based clustering inspatial databases: The algorithm gdbscan and its applications,” inDataMining and Knowledge Discovery, an Int. Journal, Kluwer AcademicPublishers, Vol. 2, No. 2, pp. 169-194., 1998.

Page 9: Extending Player/Stage/Gazebo towards Cognitive Robots ...gerkey/papers/icra07.pdfFig. 1. Cognitive Household Robotic Assistant This paper gives (1) an overview of recent additions

[13] T. H. Collett, B. A. MacDonald, and B. P. Gerkey, “Player 2.0: Towarda Practical Robot Programming Framework,” inProceedings of theAustralasian Conference on Robotics and Automation (ACRA 2005),December 2005.

[14] R. T. Vaughan, B. Gerkey, and A. Howard, “On Device Abstrac-tions For Portable, Reusable Robot Code,” inIn Proceedings ofthe IEEE/RSJ International Conference on Intelligent Robot Systems(IROS 2003), pages 2121-2427, October 2003.

[15] S. S. Intille, K. Larson, J. S. Beaudin, J. Nawyn, E. M. Tapia, andP. Kaushik, “A living laboratory for the design and evaluation ofubiquitous computing interfaces,” 2005.