ArticlePDF Available

ros_control: A generic and simple control framework for ROS

Authors:

Figures

Content may be subject to copyright.
ros_control: A generic and simple control framework for
ROS
Sachin Chitta9, 11, Eitan Marder-Eppstein1, Wim Meeussen1, Vijay
Pradeep1, Adolfo Rodríguez Tsouroukdissian12, 2, Jonathan Bohren8, 10,
David Coleman3, 11, Bence Magyar4, 2, Gennaro Raiola5, 2, Mathias
Lüdtke6, and Enrique Fernandez Perdomo7, 2
1hiDOF, Inc. (at the time of this work) 2PAL Robotics (at the time of this work) 3PickNik
Consulting 4Heriot-Watt University, Edinburgh Centre for Robotics 5Department of Advanced
Robotics, Istituto Italiano di Tecnologia (IIT) 6Fraunhofer IPA 7Clearpath Robotics 8Honeybee
Robotics 9Kinema Systems Inc. 10 John Hopkins University 11 Willow Garage Inc. (at the time of
this work) 12 Pick-it NV
DOI: 10.21105/joss.00456
Software
Review
Repository
Archive
Submitted: 09 November 2017
Published: 05 December 2017
Licence
Authors of JOSS papers retain
copyright and release the work un-
der a Creative Commons Attri-
bution 4.0 International License
(CC-BY).
Summary
In recent years the Robot Operating System (Quigley et al. 2009) (ROS) has become
the ‘de facto’ standard framework for robotics software development. The ros_control
framework provides the capability to implement and manage robot controllers with a
focus on both real-time performance and sharing of controllers in a robot-agnostic way.
The primary motivation for a sepate robot-control framework is the lack of realtime-
safe communication layer in ROS. Furthermore, the framework implements solutions for
controller-lifecycle and hardware resource management as well as abstractions on hard-
ware interfaces with minimal assumptions on hardware or operating system. The clear,
modular design of ros_control makes it ideal for both research and industrial use and
has indeed seen many such applications to date. The idea of ros_control originates from
the pr2_controller_manager framework specic to the PR2 robot but ros_control is
fully robot-agnostic. Controllers expose standard ROS interfaces for out-of-the box 3rd
party solutions to robotics problems like manipulation path planning (MoveIt! (Chitta,
Sucan, and Cousins 2012)) and autonomous navigation (the ROS navigation stack).
Hence, a robot made up of a mobile base and an arm that support ros_control doesn’t
need any additional code to be written, only a few controller conguration les and it is
ready to navigate autonomously and do path planning for the arm. ros_control also
provides several libraries to support writing custom controllers.
Figure 1: Overview
Chitta et al., (2017). ros_control: A generic and simple control framework for ROS. Journal of Open Source Software, 2(20), 456,
doi:10.21105/joss.00456
1
Figure 2: ROS Control overview
Packages and functionalities
The backbone of the framework is the Hardware Abstraction Layer, which serves as
a bridge to dierent simulated and real robots. This abstraction is provided by the
hardware_interface::RobotHW class; specic robot implementations have to inherit
from this class. Instances of this class model hardware resources provided by the robot
such as electric and hydraulic actuators and low-level sensors such as encoders and
force/torque sensors. It also allows for integrating heterogeneous hardware or swapping
out components transparently whether it is a real or simulated robot.
There is a possibility for composing already implemented RobotHW instances which is
ideal for constructing control systems for robots where parts come from dierent suppliers,
each supplying their own specic RobotHW instance. The rest of the hardware_interface
package denes read-only or read-write typed joint and actuator interfaces for abstracting
hardware away, e.g. state, position, velocity and eort interfaces. Through these typed
interfaces this abstraction enables easy introspection, increased maintainability and con-
trollers to be hardware-agnostic.
The controller_manager is responsible for managing the lifecycle of controllers, and
hardware resources through the interfaces and handling resource conicts between con-
trollers. The lifecycle of controllers is not static. It can be queried and modied at
runtime through standard ROS services provided by the controller_manager. Such
services allow to start, stop and congure controllers at runtime.
Furthermore, ros_control ships software libraries addressing real-time ROS communi-
cation, transmissions and joint limits. The realtime_tools library adds utility classes
handling ROS communications in a realtime-safe way. The transmission_interface
Chitta et al., (2017). ros_control: A generic and simple control framework for ROS. Journal of Open Source Software, 2(20), 456,
doi:10.21105/joss.00456
2
package supplies classes implementing joint- and actuator-space conversions such as: sim-
ple reducer, four-bar linkage and dierential transmissions. A declarative denition of
transmissions is supported directly with the kinematics and dynamics description in the
robot’s Universal Robot Description Format (URDF) (Willow Garage 2009) le. The
joint_limits_interface package contains data structures for representing joint limits,
methods to populate them through URDF or yaml les and methods to enforce these lim-
its. control_toolbox oers components useful when writing controllers: a PID controller
class, smoothers, sine-wave and noise generators.
The repository ros_controllers holds several ready-made controllers supporting
the most common use-cases for manipulators, mobile and humanoid robots, e.g. the
joint_trajectory_controller is heavily used with position-controlled robots to
interface with MoveIt!. Finally, control_msgs provides ROS messages used in most
controllers oered in ros_controllers.
ros_control was conceptualized by Sachin Chitta at Willow Garage Inc. and initial
design and implementation was done by Sachin Chitta (then at Willow Garage), Wim
Meussen, Vijay Pradeep and Eitan Marder-Epstein (then at HiDOF) before being released
open-source.
ros_control is released as binary packages with each new version of ROS, source code is
hosted at the ros-controls Github organization. Documentation on behaviour, interfaces,
doxygen-generated pages and tutorials can be found at ros_control and ros_controllers.
For a thorough presentation we invite the interested reader to watch the talk given at
ROSCon2014 (Adolfo Rodríguez Tsouroukdissian, n.d.).
Robots using ros_control
Being a mature framework, ros_control is widely applied to both production and re-
search platform robots. A few examples where the control system is implemented with
ros_control are:
Clearpath Robotics’ outdoor mobile robots: Grizzly, Husky, Jackal (“New Universal
Robots Driver Makes Manipulation Research Easier,” n.d.), and OTTO Motors’
industrial indoor mobile robots: OTTO 1500, OTTO 100
The “Twil” robot at Federal University of Rio Grande do Sul (Lages 2017)
The quadruped robots HyQ and HyQ2Max (Semini et al. 2011, Semini et al. (2017))
at Istituto Italiano di Tecnologia
NASA’s humanoid and biped robots: Valkyrie & Robonaut (N. A. Radford et al.
2015, Hart et al. (2014), Badger et al. (2016))
• PAL Robotics’ humanoid, biped and mobile robots: REEM, REEM-C, PMB2,
Tiago and Talos (Stasse et al. 2017)
• Shadow Robot’s anthropomorphic, highly sensorized and precise Shadow Hand
(Meier et al. 2016)
Universal Robots’ industrial arms: UR3, UR5 (Andersen 2015)
Chitta et al., (2017). ros_control: A generic and simple control framework for ROS. Journal of Open Source Software, 2(20), 456,
doi:10.21105/joss.00456
3
Robot names and credits in order of appearance: Valkyrie (Photo by NASA / Bill
Staord), Husky (Photo by Clearpath Robotics), OTTO (Photo by Otto Motors),
TIAGo (Photo by PAL Robotics), Dexterous Hand (Photo by Shadow Robot), HyQ2Max
(Photo by Istituto Italiano di Tecnologia), TALOS (Photo by PAL Robotics)
References
Adolfo Rodríguez Tsouroukdissian. n.d. “[ROSCon2014] Ros_control: An Overview.
https://vimeo.com/107507546.
Andersen, Thomas Timm. 2015. “Optimizing the Universal Robots ROS Driver. Techni-
cal University of Denmark, Department of Electrical Engineering; http://orbit.dtu.dk/en/
publications/optimizing-the-universal-robots-ros-driver(20dde139-7e87-4552-8658-dbf2cdaab24b)
.html.
Badger, Julia, Dustin Gooding, Kody Ensley, Kimberly Hambuchen, and Allison Thack-
ston. 2016. “ROS in Space: A Case Study on Robonaut 2. In Robot Operating System
(ROS), 343–73. Springer. doi:10.1007/978-3-319-26054-9_13.
Chitta, Sachin, Ioan Sucan, and Steve Cousins. 2012. “Moveit![ROS Topics]. IEEE
Robotics & Automation Magazine 19 (1). IEEE: 18–19.
Hart, Stephen, Paul Dinh, John D Yamokoski, Brian Wightman, and Nicolaus Radford.
2014. “Robot Task Commander: A Framework and IDE for Robot Application Develop-
ment. In IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS
2014), 1547–54. IEEE. doi:10.1109/IROS.2014.6942761.
Lages, Walter Fetter. 2017. “Parametric Identication of the Dynamics of Mobile Robots
and Its Application to the Tuning of Controllers in ROS.” In Robot Operating System
(ROS), 191–229. Springer. doi:10.1007/978-3-319-54927-9_6.
Meier, Martin, Guillaume Walck, Robert Haschke, and Helge J Ritter. 2016. “Dis-
tinguishing Sliding from Slipping During Object Pushing. In IEEE/RSJ Interna-
tional Conference on Intel ligent Robots and Systems (IROS 2016), 5579–84. IEEE.
doi:10.1109/IROS.2016.7759820.
“New Universal Robots Driver Makes Manipulation Research Easier. n.d. https://www.
clearpathrobotics.com/2016/02/new-universal-robots-driver-makes-manipulation-easier.
Quigley, Morgan, Ken Conley, Brian Gerkey, Josh Faust, Tully Foote, Jeremy Leibs, Rob
Chitta et al., (2017). ros_control: A generic and simple control framework for ROS. Journal of Open Source Software, 2(20), 456,
doi:10.21105/joss.00456
4
Wheeler, and Andrew Y Ng. 2009. “ROS: An Open-Source Robot Operating System.
In ICRA Workshop on Open Source Software, 3:5. 3.2. Kobe; http://www.willowgarage.
com/papers/ros-open-source-robot-operating-system.
Radford, Nicolaus A., Philip Strawser, Kimberly Hambuchen, Joshua S. Mehling,
William K. Verdeyen, A. Stuart Donnan, James Holley, et al. 2015. “Valkyrie:
NASA’s First Bipedal Humanoid Robot. Journal of Field Robotics 32 (3): 397–419.
doi:10.1002/rob.21560.
Semini, Claudio, Victor Barasuol, Jake Goldsmith, Marco Frigerio, Michele Focchi, Yifu
Gao, and Darwin G Caldwell. 2017. “Design of the Hydraulically Actuated, Torque-
Controlled Quadruped Robot HyQ2Max. IEEE/ASME Transactions on Mechatronics
22 (2). IEEE: 635–46. doi:10.1109/TMECH.2016.2616284.
Semini, Claudio, Nikos G Tsagarakis, Emanuele Guglielmino, Michele Focchi, Ferdinando
Cannella, and Darwin G Caldwell. 2011. “Design of HyQ–a Hydraulically and Electrically
Actuated Quadruped Robot. Proceedings of the Institution of Mechanical Engineers,
Part I: Journal of Systems and Control Engineering 225 (6). SAGE Publications Sage
UK: London, England: 831–49. doi:10.1109/IROS.2010.5651548.
Stasse, Olivier, Thomas Flayols, Rohan Budhiraja, Kevin Giraud-Esclasse, Justin Car-
pentier, Andrea Del Prete, Philippe Soueres, et al. 2017. “TALOS: A New Humanoid
Research Platform Targeted for Industrial Applications. https://hal.archives-ouvertes.
fr/hal-01485519.
Willow Garage. 2009. “Universal Robot Description Format (URDF).http://wiki.ros.
org/urdf/.
Chitta et al., (2017). ros_control: A generic and simple control framework for ROS. Journal of Open Source Software, 2(20), 456,
doi:10.21105/joss.00456
5
... Specifically, the replanning architecture is actually implemented by OpenMORE [161] (refer to Chapter 6). This architecture continually generates the subsequent robot command, which is transmitted to the robot's controller utilizing the ROS Control [24] framework. ...
... Simultaneously, the replanner_manager executes the robot's current trajectory while concurrently planning a new one. To transmit commands to the robot's low-level controller, the replanner can either be integrated into a ROS Controller [24] or send it the new commands using a message of type sensor_msgs::JointState. ...
... Thanks to the integration with ROS, it was possible to make the replanner interact easily with an ISO/TS15066-based speed scaling module launched on a different node. The replanner was inserted into a controller in the ROS Control framework [24] which read the commands from the replanner_manager and sent them to the robot. Figure 6.1a and 6.1b are snapshots from a simulated environment, where robots are asked to move from a start configuration to a goal configuration while some unexpected obstacles appear. ...
Thesis
Full-text available
In recent years, there has been a significant increase in robots sharing workspace with human operators, combining the speed and precision inherent to robots with human adaptability and intelligence. However, this integration has introduced new challenges in terms of safety and collaborative efficiency. Robots now need to swiftly adjust to dynamic changes in their environment, such as the movements of operators, altering their path in real-time to avoid collisions, ideally without any disruptions. Moreover, in human-robot collaborations, replanned trajectories should adhere to safety protocols, preventing safety-induced slowdowns or stops caused by the robot's proximity to the operator. In this context, quickly providing high-quality solutions is crucial for ensuring the robot's responsiveness. Conventional replanning techniques often fall short in complex environments, especially for robots with numerous degrees of freedom contending with sizable obstacles. This thesis tackles these challenges by introducing a novel sampling-based path replanning algorithm tailored for robotic manipulators. This approach exploits pre-computed paths to generate new solutions in a few hundred milliseconds. Additionally, it integrates a cost function that steers the algorithm towards solutions that comply with the ISO/TS 15066 safety standard, thereby minimizing the need for safety interventions and fostering efficient cooperation between humans and robots. Furthermore, an architecture for managing the replanning process during the execution of the robot's motion is introduced. Finally, a software tool is presented to streamline the implementation and testing of path replanning algorithms. Simulations and experiments conducted on real robots demonstrate the superior performance of the proposed method compared to other popular techniques.
... Some of most widely used ROS libraries and packages include the TF library [11], MoveIt [9], and the Navigation-stack. The ROS ecosystem of contributors additionally contains many packages for many important requirements such as simulation [26,34], kinematic modeling [47,2], and planning and control [19,36,8]. Thus, ROS offers many packages providing useful functionalities for both research and commercial applications. These packages include valuable data structures, control interfaces, inverse kinematics (IK) and motion planning tools, perception utilities, and various visualizers. ...
Preprint
We present a framework for intuitive robot programming by non-experts, leveraging natural language prompts and contextual information from the Robot Operating System (ROS). Our system integrates large language models (LLMs), enabling non-experts to articulate task requirements to the system through a chat interface. Key features of the framework include: integration of ROS with an AI agent connected to a plethora of open-source and commercial LLMs, automatic extraction of a behavior from the LLM output and execution of ROS actions/services, support for three behavior modes (sequence, behavior tree, state machine), imitation learning for adding new robot actions to the library of possible actions, and LLM reflection via human and environment feedback. Extensive experiments validate the framework, showcasing robustness, scalability, and versatility in diverse scenarios, including long-horizon tasks, tabletop rearrangements, and remote supervisory control. To facilitate the adoption of our framework and support the reproduction of our results, we have made our code open-source. You can access it at: https://github.com/huawei-noah/HEBO/tree/master/ROSLLM.
... The ros control framework was used to implement the new controller (Chitta et al., 2017). These packages follow the structure shown in Figure 4. ...
Conference Paper
Full-text available
The robot TIAGo is a mobile manipulator developed by PAL Robotics. It combines perception, navigation, manipulation and human-robot interaction skills. The purpose of this work is to review the main teleoperation techniques available out-of-the-box to control this robot and move both its base and its joints. Additionally, this paper describes a new ROS controller designed to move TIAGo’s arm (which has 7 degrees of freedom), which accepts Cartesian input from a 3D mouse used in CAD applications, repur�posed as a teleoperation control interface. Its behavior has been tested in a virtual environment within the Gazebo simulator, and validated against the actual robot in the context of a pick-and-place task involving the manipulation of objects in a real environment.
... As already mentioned, the backbone of the presented architecture is based on the Robot Operating System (ROS) [Quigley et al., 2009]. In particular, the whole robot control software has been realized using ROS Noetic on an Ubuntu 20.04 machine, leveraging the built-in functionalities of ros control [Chitta et al., 2017] and MoveIt! [Coleman et al., 2014]. ...
Preprint
Full-text available
Individuals with diverse motor abilities often benefit from intensive and specialized rehabilitation therapies aimed at enhancing their functional recovery. Nevertheless, the challenge lies in the restricted availability of neurorehabilitation professionals, hindering the effective delivery of the necessary level of care. Robotic devices hold great potential in reducing the dependence on medical personnel during therapy but, at the same time, they generally lack the crucial human interaction and motivation that traditional in-person sessions provide. To bridge this gap, we introduce an AI-based system aimed at delivering personalized, out-of-hospital assistance during neurorehabilitation training. This system includes a rehabilitation training device, affective signal classification models, training exercises, and a socially interactive agent as the user interface. With the assistance of a professional, the envisioned system is designed to be tailored to accommodate the unique rehabilitation requirements of an individual patient. Conceptually, after a preliminary setup and instruction phase, the patient is equipped to continue their rehabilitation regimen autonomously in the comfort of their home, facilitated by a socially interactive agent functioning as a virtual coaching assistant. Our approach involves the integration of an interactive socially-aware virtual agent into a neurorehabilitation robotic framework, with the primary objective of recreating the social aspects inherent to in-person rehabilitation sessions. We also conducted a feasibility study to test the framework with healthy patients. The results of our preliminary investigation indicate that participants demonstrated a propensity to adapt to the system. Notably, the presence of the interactive agent during the proposed exercises did not act as a source of distraction; instead, it positively impacted users' engagement.
... The AR scene was developed on the Unity engine with MRTK3 and was deployed on Microsoft HoloLens 2 AR-HMD. The software system was developed and integrated using the ROS 2 [34], MoveIt 2 [35] and ros2 control [36]. ...
Preprint
Current orthopedic robotic systems largely focus on navigation, aiding surgeons in positioning a guiding tube but still requiring manual drilling and screw placement. The automation of this task not only demands high precision and safety due to the intricate physical interactions between the surgical tool and bone but also poses significant risks when executed without adequate human oversight. As it involves continuous physical interaction, the robot should collaborate with the surgeon, understand the human intent, and always include the surgeon in the loop. To achieve this, this paper proposes a new cognitive human-robot collaboration framework, including the intuitive AR-haptic human-robot interface, the visual-attention-based surgeon model, and the shared interaction control scheme for the robot. User studies on a robotic platform for orthopedic surgery are presented to illustrate the performance of the proposed method. The results demonstrate that the proposed human-robot collaboration framework outperforms full robot and full human control in terms of safety and ergonomics.
... Algorithm 1 is coded in Python 3, with the NN implemented with PyTorch [51], interfacing with the other modules via ROS communication mechanisms [52]; the impedance controller in (2) and the direct force control law in (5) are both implemented in C++ inheriting the ROS control framework interfaces [53]. Robot states and dynamic matrices used in (2) are retrieved via software with libfranka 1 , which also exposes an interface to retrieve the EE wrenches h e , estimated by an internal algorithm from joint torque measurements. ...
Preprint
Full-text available
In industrial settings, robotic tasks often require interaction with various objects, necessitating compliant manipulation to prevent damage while accurately tracking reference forces. To this aim, interaction controllers are typically employed, but they need either human tinkering for parameter tuning or precise environmental modeling. Both these aspects can be problematic, as the former is a time-consuming procedure, and the latter is unavoidably affected by approximations, hence being prone to failure during the actual application. Addressing these challenges, current research focuses on devising high-performance force controllers. Along this line, this work introduces ORACLE ( O ptimized R esidual A ction for Interaction C ontrol with L earned E nvironments), a novel force control approach. Utilizing neural networks, ORACLE predicts robot-environment interaction forces, which are then used in an optimal residual action controller to locally correct actions from a base force controller, minimizing the expected force-tracking error. Tested on a real Franka Emika Panda robot, ORACLE demonstrates superior force tracking performance compared to state-of-the-art controllers, with a short setup time.
Article
Industrial robots performing complex operations often require remote control. The operator must have access to configure the robot behavior, set operations, simulate operation execution before execution, synchronize robot and its digital model state, change the control mode if necessary. Virtual reality interfaces allow to control robots interactively and perform all the operations described above. The article proposes an implementation of a control system based on virtual reality interfaces, which allows real-time control of an industrial robot. The proposed solution has been tested on two robots and includes a universal (iterative) inverse kinematics solver, a trajectory planner, a tasks scheduler, supports work in master-slave and trajectory modes.
Thesis
Full-text available
The present dissertation contributes to facilitating the transformation of industrial composting plants towards standards of Industry 4.0. Optimization potentials are analyzed, and systematic-methodical approaches to solutions are developed. The focus is on the investigation within a technical-logistic context. Thus, the dissertation addresses two key research objectives: the development of an autonomous, intelligent compost turner, and a comprehensive hyperconnected platform for heavy-duty machinery sharing.
Conference Paper
Full-text available
This paper introduces the Robot Task Commander (RTC) framework for defining, developing, and deploying robot application software for use in different run-time contexts. RTC was created by NASA-JSC in conjunction with General Motors for use with the Robonaut-2 and Valkyrie humanoid robot platforms. RTC provides a robot programming syntax and an IDE appropriate for use by experts and non-experts for implementation and execution. An expert developer can implement a new application with a combination of scripts, called process nodes, and state machines that set the control mode of the robot. A non-expert developer can assemble process nodes and controller state machines into novel hierarchical applications using a visual programming language (VPL). This VPL also allows developers to interface with other RTC applications or with third-party software packages using a variety of network transport mechanisms (ROS, TCP, shared memory, etc.). RTC represents an advantage over other robot programming frameworks by providing multiple levels of flexibility for development. The efficacy of RTC is demonstrated through examples of sophisticated behaviors, such as programming the Valkyrie robot to grab objects and turn a valve.
Article
Full-text available
In December 2013, 16 teams from around the world gathered at Homestead Speedway near Miami, FL to participate in the DARPA Robotics Challenge (DRC) Trials, an aggressive robotics competition partly inspired by the aftermath of the Fukushima Daiichi reactor incident. While the focus of the DRC Trials is to advance robotics for use in austere and inhospitable environments, the objectives of the DRC are to progress the areas of supervised autonomy and mobile manipulation for everyday robotics. NASA's Johnson Space Center led a team comprised of numerous partners to develop Valkyrie, NASA's first bipedal humanoid robot. Valkyrie is a 44 degree-of-freedom, series elastic actuator-based robot that draws upon over 18 years of humanoid robotics design heritage. Valkyrie's application intent is aimed at not only responding to events like Fukushima, but also advancing human spaceflight endeavors in extraterrestrial planetary settings. This paper presents a brief system overview, detailing Valkyrie's mechatronic subsystems, followed by a summarization of the inverse kinematics-based walking algorithm employed at the Trials. Next, the software and control architectures are highlighted along with a description of the operator interface tools. Finally, some closing remarks are given about the competition, and a vision of future work is provided.
Chapter
This tutorial chapter explains the identification of dynamic parameters of the dynamic model of wheeled mobile robots. Those parameters depend on the mass and inertia parameters of the parts of the robot and even with the help of modern CAD systems it is difficult to determine them with a precision as the designed robot is not built with 100% accuracy; the actual materials have not exactly the same properties as modeled in the CAD system; there is cabling which density changes over time due to robot motion and many other problems due to differences between the CAD model and the real robot. To overcome these difficulties and still have a good representation of the dynamics of the robot, this work proposes the identification of the parameters of the model. After an introduction to the recursive least-squares identification method, it is shown that the dynamic model of a mobile robot is a cascade between its kinematic model, which considers velocities as inputs, and its dynamics, which considers torques as inputs and then that the dynamics can be written as a set of equations linearly parameterized in the unknown parameters, enabling the use of the recursive least-squares identification. Although the example is a differential-drive robot, the proposed method can be applied to any robot model that can be parameterized as the product of a vector of parameters and a vector of regressors. The proposed parameter identification method is implemented in a ROS package and can be used with actual robots or robots simulated in Gazebo. The package for the Indigo version of ROS is available at http://www.ece.ufrgs.br/twil/indigo-twil.tgz. The chapter concludes with a full example of identification and the presentation of the dynamic model of a mobile robot and its use for the design of a controller. The controller is based on three feedback loops. The first one linearizes the dynamics of the robot by using feedback linearization, the second one uses a set of PI controllers to control the dynamics of the robot, and the last one uses a non-linear controller to control the pose of the robot.
Chapter
Robonaut 2 (R2), an upper-body dexterous humanoid robot, was developed in a partnership between NASA and General Motors. R2 has been undergoing experimental trials on board the International Space Station (ISS) for more than two years, and has recently been integrated with a mobility platform. Once post-integration checkouts are complete, it will be able to maneuver around the ISS in order to complete tasks and continue to demonstrate new technical competencies for future extravehicular activities. The increase in capabilities requires a new software architecture, control and safety system. These have all been implemented in the ROS framework. This case study chapter will discuss R2’s new software capabilities, user interfaces, and remote deployment and operation, and will include the safety certification path taken to be able to use ROS in space.