Skip to main content

ORIGINAL RESEARCH article

Front. Robot. AI, 18 August 2017
Sec. Soft Robotics
Volume 4 - 2017 | https://doi.org/10.3389/frobt.2017.00039

Integrating Soft Robotics with the Robot Operating System: A Hybrid Pick and Place Arm

imageRoss M. McKenzie imageThomas W. Barraclough imageAdam A. Stokes*
  • Stokes Research Group, The School of Engineering, The University of Edinburgh, Edinburgh, United Kingdom

Soft robotic systems present a variety of new opportunities for solving complex problems. The use of soft robotic grippers, for example, can simplify the complexity in tasks such as the grasping of irregular and delicate objects. Adoption of soft robotics by the informatics community and industry, however, has been slow and this is, in-part, due to the amount of hardware and software that must be developed from scratch for each use of soft system components. In this paper, we detail the design, fabrication, and validation of an open-source framework that we designed to lower the barrier to entry for integrating soft robotic subsystems. This framework is built on the robot operating system (ROS), and we use it to demonstrate a modular, soft–hard hybrid system, which is capable of completing pick and place tasks. By lowering this barrier to entry through our open sourced hardware and software, we hope that system designers and Informatics researchers will find it easy to integrate soft components into their existing ROS-enabled robotic systems.

Introduction

The lack of open source hardware and software for soft robotics creates a significant barrier to entry for researchers who wish to conduct research into soft robotic systems. In this paper, we detail our development of an open source, modular, soft–hard hybrid robot whose components can be easily manufactured and integrated into existing or robotic systems. By lowering this barrier to entry, we aim to provide the informatics community with a new opportunity to explore the benefits of soft robotics for a wide range of tasks.

A robotic system contains a combination of hardware, sensing, and control. The established control paradigms for hard robot systems are based on assumptions that the links in an assembly are rigid, and that the joint angles can be measured using encoders. Soft robotic components do not have rigid links and so the established control methods cannot be applied (Ross et al., 2016). Soft robotics researchers require control-hardware and control-software, which is designed for their specific actuation and sensing techniques.

The advantages of integrating soft robotic components with other types of robotic systems is demonstrated by their use in haptic classification (used in combination with a Baxter robot) (Homberg et al., 2015) and in object retrieval (used in combination with a Roomba wheeled-hard robot) (Stokes et al., 2014). These two examples are hybrids and share many common system components, but the system designers used their own bespoke control systems. This repetition of existing work slows the rate of soft robotic research and reduces innovation. There are some resources available to researchers when they are designing and fabricating the soft components themselves. Ilievski et al. (2011) detail the fabrication of soft robotic actuators, pneunets. Pneunets are pneumatic-channels, which are molded into the interior of a soft robot and they actuate by expanding due to pressurized gas. Instructions for building the specific soft grippers, we use in this paper, are presented in a step-by-step format by Finio et al. (2013). This existing body of work means that researchers without a materials science background have enough information to fabricate soft robotic grippers.

Another significant resource is the soft robotic toolkit (Harvard Biodesign Lab, 2016). This website holds a repository of information on soft robotics and also includes an open source design for a manual pneumatic control board. This board contains a microcontroller in order to enact human inputs (from potentiometers) and, therefore, could be adapted for automatic control by adding custom code. However, it uses a number of bread boards with wiring in between and is, therefore, large. Our design of a compact circuit board with an included program for computer control will be easier to integrate into other robotic designs.

The resources for building a full robotic system, which integrates hard and soft components are much more limited. The open source hardware and software, which we present in this paper provide a new resource for research into integrated soft robotic systems and will lower the barrier to entry for researchers. We provide easy to fabricate modules for: (1) a hard robotic arm; (2) a soft robotic gripper; and (3) the electronics and software used to build a fully controlled system.

Robotic grasping can use a number of methods that fall into two main groups: (1) fingertip grasps, when an object is pinched between contact points and (2) enveloping grasps, where the fingers and palm of a gripper wrap around an object (Bicchi and Kumar, 2000). Enveloping grasps are better at restraining objects but can be difficult to achieve with hard robotics unless the shape and size of the target object are known before the gripper is developed. By making grippers soft an enveloping grasp becomes much easier as the gripper can conform to the shape of an object without external control (Ilievski et al., 2011). These soft grippers can also handle more delicate objects, such as fruit (Tedford, 1990; van Henten et al., 2002; Soft Robotics Inc, 2016) and biological samples (Galloway et al., 2016).

There are numerous designs and actuation methods for soft grippers, such as those that use the jamming properties of granular materials under a vacuum (Amend et al., 2012), electro-adhesion (Shintake et al., 2016), shape memory alloys (Wang et al., 2016), gecko-inspired adhesion (Song et al., 2017), and capillary action (Arutinov et al., 2015). We used the four fingered pneumatic soft gripper as detailed in Finio et al. (2013). We chose this gripper because the fabrication process is well documented. To simplify the control system, we used a single pneumatic control line, rather than having a separate channel in each finger.

By using a hybrid hard–soft system, we allow the robot to use the advantages of both hard and soft robotics. This idea was demonstrated in our previous work, Stokes et al. (2014), where we showed that the advantages of speed and accuracy offered by hard robotics could be combined with the versatility of soft robotics. We use a similar design strategy here, for a pick and place task. For this grasping and manipulation task, precise and fast positioning of the end effector is best achieved by a hard robotic arm, while a soft gripper produces a soft enveloping grip that is tolerant to positioning error and object irregularity.

Standardization allows researchers to combine work from multiple sources without having to spend time creating bespoke adaptors or recreating incompatible work. This reduction in time spent on non-novel work means that standardization is an important step in fostering innovation. An example of this benefit of standardization is found in the standardized control language (G-Code) used in Computer Numerical Control (CNC) machines (E. I. Association and A. N. S. Institute, 1980). Before this standardization, each manufacturer had used their own language and it was difficult for companies to change machines making innovation difficult to propagate. Similarly, innovation in soft robotics is currently held back by the need to implement a bespoke control system for each new robotic system.

Robotics is moving toward standardization and commercially available robots such as the Baxter (Rethink Robotics, 2016) and PR2 (Garage, 2016) are designed to work with a standardized software system called the robotic operating system (ROS). (ROS Contributers, 2016) ROS is a framework that allows for easy integration of ROS packages, which have different functionalities. This ease of integration is enabled by using independent nodes to run programs while enabling communication through message carriers called topics. These nodes and topics have standardized protocols allowing easy use of other researcher’s individual nodes and topics or structures of multiple nodes and topics.

This standardized system encourages collaborative development by allowing different researchers to quickly find and use the work of others, which has been published in the global ROS package repository. This collaborative approach avoids the need for researchers to repeat the work of others when creating their new research platform. We chose ROS as our system controller to make it easier to integrate our whole system, or its modular components, with other robots—for example a wheeled platform.

Design of a Modular, Open Source, Hybrid System for Pick and Place Tasks

Pick and place tasks are found in a variety of industrial processes. Many pick and place tasks, such as those in agriculture or ecommerce order fulfillment, have not been automated due to the requirement for delicate or compliant grasping (Rodríguez et al., 2013) and the variety in size, shape, and rigidity of the target objects involved (Liang et al., 2015). By designing this open source package around a pick and place task, we can demonstrate integration of both hard and soft modules into a system, which is capable of performing task-oriented work. Figure 1 provides an overview of the system. Software and schematics for the system are open source and are available at: http://www.homepages.ed.ac.uk/astokes2/research_BSR.html#ROS.

FIGURE 1
www.frontiersin.org

Figure 1. An overview of the open source system. (A) A picture of the soft–hard hybrid arm. (B) A block diagram of the system.

Design of the Control Software

Design of the ROS Control

We designed our software to be modular; the ROS nodes execute specific tasks and it is easy to exchange them for new nodes. The arm control is, therefore, completely separate from the soft robotic control. We spanned the hard and soft control sections of the code with an overall system controller node, which sends instructions to the arm and to the pneumatic controllers. The system controller also monitors the hard and soft controllers so that it can wait for an instruction to be completed before issuing another. Figure 2 shows the layout of the ROS nodes and topics.

FIGURE 2
www.frontiersin.org

Figure 2. A graph showing the organization of ROS nodes and topics used to control the system. The soft robotic control is in the top half while the bottom half is the arm control.

3-Axis Control

There are pre-existing ROS packages for motion planning with robot arms, such as MoveIt! (Sucan and Chitta, 2016) however, these packages are designed to control complex research-arms with more than three degrees of freedom. For our simple rigid link robot arm, we designed a new program, which uses analytical inverse kinematic solutions to determine required joint angles to reach a Cartesian coordinate published in the arm control topic. The program then finds the nearest space possible with the discrete steps of each motor and updates the joint angles and Cartesian position with their true values.

PID Control

The pressure control node runs a PID loop using the values published by the pressure sensor. This design allows initial actuation to the component and it maintains pressure over time. We designed the controller to maintain pressure between an upper and lower boundary to avoid rapid oscillations in the applied pressure.

Design of the Hardware

The Design of the Embedded Electropneumatic Control System

To allow direct control from a PC, we used a Ronex Board from Shadow robotics (Shadow Robotics, 2016). The Ronex board provides two 5 V power sources and 12 5 V Digital Input/Output (IO) pins. The board is fully ROS enabled and so our ROS nodes could easily control the electropneumatic system.

Our system also comprised a motor board and a pneumatic control board. The motor board is designed to run three stepper motors using six IO pins while the pneumatic control board uses four IO pins to run a pump, valve and pressure sensor.

Design of the Rigid Link Robot Arm

We based the arm on an existing open source arm design, the Dobot arm (Shenzhen Yuejiang Technology Co. Ltd, 2016), which we altered to be lightweight and easier to manufacture using our available tools. The arm involves a parallel linkage so that the end effector is always parallel to the surface upon which the arm is positioned. This feature removes some of the complexity in controlling the arm.

Our arm does not require the precision of industrial robotic arms as the wide, enveloping grasp of our mounted soft gripper allows for the robust grasping of objects that are not directly beneath the end effector. Our system can accomplish manipulation tasks reliably and only costs around $100, including the pneumatic system, but excluding the Ronex board. Conventional research arms for similar tasks, for example a Kuka YouBot arm (youBot Store GmbH, 2016), can cost around $18,000 and hobbyist arms, such as the official Dobot arm, will cost $900 (Shenzhen Yuejiang Technology Co. Ltd, 2016). These arms are designed to have micrometer precision, as conventional robotic grippers can only tolerate a low error rate when picking up small or complex objects. By removing this requirement, our arm can be made cheaper by an order of magnitude, as it does not need highly accurate motors, encoders, and force sensors on the joints and can be made from low-cost plastic.

Design of the Soft Robotic Gripper

We used the design for a soft gripper detailed in Finio et al. (2013).

Experimental Design

Design of Validation Experiments

The arm must operate below a reasonable level of position error, not stall its motors and not accumulate position error over time through loss of steps. We tested these three factors by instructing the arm to make six 50 cm movements within its plane, and then we measured its position. Analysis of these results will enable us to find the positioning error in these movements. After each motion, we instructed the arm to return to its exact starting location and we measured the difference between the start and end locations to obtain another error value. This error allows us to determine if steps are being lost by the motors, because the arm should return to the same starting position. We calculated the mean-error for position and step-loss in the horizontal and vertical directions. The systematic error in the measurements is 0.05 mm from the Vernier caliper.

We performed a similar test with rotation by instructing the arm to turn 90° and then return to its starting position, we measured the error after each motion and three repeats were used. The systematic error in this measurement is 0.5° arising from the protractor.

We also performed a test on end effector backlash, i.e., how far the end effector could be moved without forcing the motors. We performed this test by moving the end effector by hand in three perpendicular directions, and we measured the distance between extreme positions. We estimated the measurement error in this method to be 0.5 mm.

Design of the Soft Grasping and Manipulation Task

To test the ability of the arm to grasp and manipulate objects, we placed a target box and a target object on a table. We chose the position so that the height of the end effector and rotation and extension of the arm would all need to change in order for the task to succeed. To test the delicacy of the soft gripping, we chose one object, a tomato. We chose a second object, a syringe, as it had an asymmetric shape. These two shapes allowed us to test the ability of the gripper to pick up objects using the same control input. The only change made to the instructions between the two tests was to place the end effector 1 cm lower during the syringe grasp to account for the difference in height.

Results and Discussion

System Fabrication and Verification

We fabricated the arm using a combination of 3D printed and laser cut components. We fabricated the soft gripper using Ecoflex 00-50 and a 3D printed mold. Further assembly information is included in the experimental section.

Evaluation of Arm Performance

Table 1 shows the results of the validation tests. The arm is precise enough to provide a platform for a soft gripper. This is due to the compliance in the gripper allowing for an alignment error that is greater than the error in end effector position. Its end effector, however, can be moved perpendicular to the plane of the arm by 1 cm. The backlash in this direction could mean that it is not guaranteed to perform well in soft grasping tasks with small (2–3 cm across) grippers. This result is mitigated as we measured from extreme to extreme and so the true effect on precision is only 0.5 cm. The end effector also returns to the same rest position when released and so letting the arm settle after each movement removes the effect of the backlash. This backlash error arises from non-perfect fits between parts of the arm as well as deformation in the material of the arm. In comparison, the Dobot arm has a precision of 0.2 mm (Shenzhen Yuejiang Technology Co. Ltd, 2016).

TABLE 1
www.frontiersin.org

Table 1. The results of the validation test.

Table 1 shows the results of our tests to assess increasing inaccuracy over time due to step loss. Using the starting height of the position error tests and assuming that the second joint was vertically downwards, we calculated the joint angles to be 65° for the first and 90° for the second joint. The change of one step (1.8°) in either direction from either joint will produce a minimum of 4.3 mm positioning error. This result demonstrates that our arm is not losing steps. The error is caused by our use of microstepping (University of Texas, 2016), which is a method used to give stepper motors a higher resolution than their step size. Microstepping can cause hysteresis, which is why our motors did not return to their exact starting location. This effect does not cause accumulation of position error over time.

Results of the Pick and Place Task

We instructed the arm to execute the two manipulation tasks and it functioned correctly and within an acceptable level of precision. This is demonstrated by two separate videos at:

http://edin.ac/2cKLWKS

http://edin.ac/2ccasze

These videos demonstrate the ability of our system to pick up both regularly and irregularly shaped objects with the same control input to the simple soft gripper. Figure 3 shows snapshots from the tomato manipulation test.

FIGURE 3
www.frontiersin.org

Figure 3. Still frames from a video of the arm performing a manipulation task with a tomato. In this task, a tomato is grasped, manipulated, and placed in a box. Frames at: (A) 0s, (B) 27s, (C) 41s, (D) 45s and (E) 52s.

Scope for Development

Improvements to Arm Accuracy

As the arm was only losing one step after an average of two motions, the loss of steps is unlikely to be the cause of the imprecision. The inverse kinematics were checked by hand and are accurate. Therefore, the main cause of inaccuracy in the arm must have been caused by the inaccuracy in its starting location being propagated through the inverse kinematics. Introducing sensors to the arm, such as end stops or hall effect sensors would provide a way to determine an accurate starting position at every restart.

Gearboxes could further reduce the chance of the arm stalling by increasing torque but would reduce travel speed.

Additional Modules for the ROS Packages

We designed the open source package to be modular and as such more nodes can be added to it. These could include curvature sensors such as were demonstrated by Homberg et al. (2015) or nodes to control other actuation methods such as a vacuum pump to run a jamming gripper such as the one demonstrated by Amend et al. (2012).

Integration with Other Platforms

The use of ROS to create our control software allows it to be used with other ROS packages. As an example if we were to recreate our previous work in Stokes et al. (2014) with a more autonomous system, we could use available packages to reduce the time needed to have a working solution. In this solution, we would use the create_autonomy (Perron, 2017) ROS package as a driver for the motors and sensors. By setting the appropriate topic names in this package, we can use the tf (Foote et al., 2017), gmapping (Gerkey, 2017), and navigation (Marder-Eppstein, 2017) packages to allow the robot to automatically map its surroundings and plan paths to targets. These packages are well documented and have specific tutorials for using all three together (Joseph, 2015). To control the soft walker, we would use four of the pressure control boards from this paper run with four pressure control nodes in parallel. We would need to write a ROS node that could create the correct pressure and timing patterns for soft walker locomotion, which are already known. This work could be turned into a new ROS package to save on future work and even interface with the navigation package for soft walker path planning. We would also need a node that tells the robot its target, based on a map landmark or light source. This work would produce a fully autonomous, hybrid robotic system with the majority of its code from preexisting sources.

Conclusion

The lack of open source resources for those who wish to conduct research with soft robotics impedes progress in two areas: (1) engineering work on soft robotics is impeded due to a lack of standardization and the time spent recreating the work done by others and (2) the need to create bespoke hardware provides a significant barrier to entry for those whose primary research field is informatics rather than engineering.

Our work provides the first open-source computer control system specifically developed for soft robotics that includes hardware and software. Additionally, we have designed, fabricated, and demonstrated the first open-source soft–hard hybrid robot for gripping and manipulation tasks.

By creating this resource for soft robotics, we aim to allow informatics researchers to integrate soft robotic systems with existing robots using our software package. We also aim to allow these researchers to use soft robotics without needing to design hardware through open sourcing our own designs. This step toward standardization should allow for further research into the control of soft robotics and the use of soft robotics for complex tasks.

Soft robotics researchers will also benefit from our work as they have the option of a standardized controller, which will integrate with other robotics platforms and, therefore, they do not need to recreate all the hardware and software from scratch.

Further software created to integrate with our package for the control of soft robotic systems can be used to create a library of soft robot ROS packages. This library could allow for soft robotic systems that are as simple to set up and use as current off the shelf robots.

Our platform need not only serve an academic purpose as we have used it to demonstrate the ability of a simple hybrid system to complete pick and place tasks. This work could provide a basis for the industrial development of soft–hard hybrid automation solutions.

Author Contributions

RM—design, fabrication, experimentation, and writing. TB—design and writing. AS—design and writing.

Conflict of Interest Statement

The authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Funding

This study was supported by EPSRC via the Robotarium Capital Equipment and CDT Capital Equipment Grants (EP/L016834/1) and the CDT in Robotics and Autonomous Systems.

References

Amend, J. R., Brown, E., Rodenberg, N., Jaeger, H. M., and Lipson, H. (2012). A positive pressure universal gripper based on the jamming of granular material. IEEE Trans. Robot. 28, 341–350. doi: 10.1109/TRO.2011.2171093

CrossRef Full Text | Google Scholar

Arutinov, G., Mastrangeli, M., van Heck, G., Lambert, P., den Toonder, J. M. J., Dietzel, A., et al. (2015). Capillary gripping and self-alignment: a route toward autonomous heterogeneous assembly. IEEE Trans. Robot. 31, 1033–1043. doi:10.1109/TRO.2015.2452775

CrossRef Full Text | Google Scholar

Bicchi, A., and Kumar, V. (2000). “Robotic grasping and contact: a review,” in IEEE International Conference on Robotics and Automation, San Francisco, 1.

Google Scholar

E. I. Association A. N. S. Institute. (1980). Interchangeable Variable Block Data Format for Positioning, Contouring, and Contouring/Positioning Numerically Controlled Machines. Washington, DC: The Department.

Google Scholar

Finio, B., Shepherd, R., and Lipson, H. (2013). “Air-powered soft robots for K-12 classrooms,” in 3rd IEEE Integrated STEM Education Conference, Princeton.

Google Scholar

Foote, T., Marder-Eppstein, E., and Meeussen, W. (2017). tf [Online]. Available at: http://wiki.ros.org/tf

Google Scholar

Garage, W. (2016). Willow Garage—PR2 [Online]. Available at: http://www.willowgarage.com/pages/pr2/overview

Google Scholar

Galloway, K. C., Becker, K. P., Phillips, B., Kirby, J., Licht, S., Tchernov, D., et al. (2016). Soft robotic grippers for biological sampling on deep reefs. Soft Robot. 3, 23–33. doi:10.1089/soro.2015.0019

PubMed Abstract | CrossRef Full Text | Google Scholar

Gerkey, B. (2017). Gmapping [Online]. Available at: http://wiki.ros.org/gmapping

Google Scholar

Homberg, B., Katzschmann, R., Dogar, M., and Rus, D. (2015). “Haptic identification of objects using a modular soft robotic gripper,” in IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Hamburg.

Google Scholar

Harvard Biodesign Lab. (2016). The Soft Robotics Toolkit [Online]. Available at: http://softroboticstoolkit.com/

Google Scholar

Ilievski, F., Mazzeo, A. D., Shepherd, R. F., Chen, X., and Whitesides, G. M. (2011). Soft robotics for chemists. Angew. Chem. Int. Ed. 50, 1890–1895. doi:10.1002/anie.201006464

CrossRef Full Text | Google Scholar

Joseph, L. (2015). Mastering ROS for Robotics Programming, 1st Edn. Birmingham: PACKT.

Google Scholar

Liang, C., Chee, K., Zou, Y., Zhu, H., Causo, A., Vidas, S., et al. (2015). “Automated robot picking system for E-commerce fulfillment warehouse application,” in The 14th IFToMM World Congress (Taipei).

Google Scholar

Marder-Eppstein, E. (2017). Navigation [Online]. Available at: http://wiki.ros.org/navigation

Google Scholar

Perron, J. (2017). Create_Autonomy [Online]. Available at: http://wiki.ros.org/create_autonomy

Google Scholar

Rethink Robotics. (2016). Rethink Robotics—Baxter [Online]. Available at: http://www.rethinkrobotics.com/baxter/

Google Scholar

Rodríguez, F., Moreno, J. C., Sánchez, J. A., and Berenguel, M. (2013). “Grasping in Agriculture: State-of-the-Art,” in Grasping in Robotics. London: Springer-Verlag, 385–409.

Google Scholar

Ross, D., Nemitz, M. P., and Stokes, A. A. (2016). Controlling and simulating soft robotic systems: insights from a thermodynamic perspective. Soft Robot. 3, 170–176. doi:10.1089/soro.2016.0010

CrossRef Full Text | Google Scholar

ROS Contributers. (2016). ROS [Online]. Available at: http://www.ros.org/

Google Scholar

Shadow Robotics. (2016). Shadow Robotics—Ronex Board [Online]. Available at: http://www.shadowrobot.com/products/ronex/

Google Scholar

Shenzhen Yuejiang Technology Co. Ltd. (2016). Dobot [Online]. Available at: http://dobot.cc

Google Scholar

Shintake, J., Rosset, S., Schubert, B., Floreano, D., and Shea, H. (2016). Versatile soft grippers with intrinsic electroadhesion based on multifunctional polymer actuators. Adv. Mater. 28, 231–238. doi:10.1002/adma.201504264

PubMed Abstract | CrossRef Full Text | Google Scholar

Soft Robotics Inc. (2016). Homepage [Online]. Available at: http://www.softroboticsinc.com/

Google Scholar

Song, S., Drotlef, D.-M., Majidi, C., and Sitti, M. (2017). Controllable load sharing for soft adhesive interfaces on three-dimensional surfaces. Proc. Natl. Acad. Sci. U.S.A. 114, E4344–E4353. doi:10.1073/pnas.1620344114

PubMed Abstract | CrossRef Full Text | Google Scholar

Stokes, A., Shepherd, R., Morin, S., Ilievski, F., and Whitesides, G. (2014). A hybrid combining hard and soft robots. Soft Robot. 1, 70–74. doi:10.1089/soro.2013.0002

CrossRef Full Text | Google Scholar

Sucan, I. A., and Chitta, S. (2016). MoveIt! [Online]. Available at: http://moveit.ros.org/

Google Scholar

Tedford, J. D. (1990). Developments in Robot Grippers for Soft Fruit Packing in New Zealand, Vol. 8. Cambridge: University Press, 5.

Google Scholar

University of Texas. (2016). Microstepping [Online]. Available at: http://users.ece.utexas.edu/~valvano/Datasheets/StepperMicrostep.pdf

Google Scholar

van Henten, E. J., Hemming, J., van Tuijl, B. A. J., Kornet, J. G., Meuleman, J., Bontsema, J., et al. (2002). An autonomous robot for harvesting cucumbers in greenhouses. Auton. Robots 13, 241–258. doi:10.1023/A:1020568125418

CrossRef Full Text | Google Scholar

Wang, W., Rodrigue, H., Kim, H.-I., Han, M.-W., and Ahn, S.-H. (2016). Soft composite hinge actuator and application to compliant robotic gripper. Compos. Part B Eng. 98, 397–405. doi:10.1016/j.compositesb.2016.05.030

CrossRef Full Text | Google Scholar

youBot Store GmbH. (2016). Kuka, “youBot Price List,” [Online]. Available at: http://www.youbot-store.com/pricelist

Google Scholar

Keywords: soft robotics, robot operating system, robotic manipulation, open source, modular robotics

Citation: McKenzie RM, Barraclough TW and Stokes AA (2017) Integrating Soft Robotics with the Robot Operating System: A Hybrid Pick and Place Arm. Front. Robot. AI 4:39. doi: 10.3389/frobt.2017.00039

Received: 22 May 2017; Accepted: 31 July 2017;
Published: 18 August 2017

Edited by:

Barbara Mazzolai, Fondazione Istituto Italiano di Technologia, Italy

Reviewed by:

Robert Shepherd, Cornell University, United States
Massimo Mastrangeli, Max Planck Institute for Intelligent Systems (MPG), Germany

Copyright: © 2017 McKenzie, Barraclough and Stokes. This is an open-access article distributed under the terms of the Creative Commons Attribution License (CC BY). The use, distribution or reproduction in other forums is permitted, provided the original author(s) or licensor are credited and that the original publication in this journal is cited, in accordance with accepted academic practice. No use, distribution or reproduction is permitted which does not comply with these terms.

*Correspondence: Adam A. Stokes, adam.stokes@ed.ac.uk

Download