Skip to content

Commit

Permalink
Add Tests and Linter (#63)
Browse files Browse the repository at this point in the history
* Add tests for tcp sender

* Add linter and pre-commit hooks

* Reformat with python black

* Add tests

* Add tests for server, client, publisher, subscriber, ros_service, unity_service, thread_pauser

* Fix pre-commit-config file name; Add client tests

* Add github workflow check

* Formatting
  • Loading branch information
sdiao authored and peifeng-unity committed Jul 15, 2021
1 parent 92fab0e commit 6db5d23
Show file tree
Hide file tree
Showing 10 changed files with 150 additions and 77 deletions.
2 changes: 1 addition & 1 deletion .github/PULL_REQUEST_TEMPLATE.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ Provide any relevant links here.

## Testing and Verification

Please describe the tests that you ran to verify your changes. Please also provide instructions, ROS packages, and Unity project files as appropriate so we can reproduce the test environment.
Please describe the tests that you ran to verify your changes. Please also provide instructions, ROS packages, and Unity project files as appropriate so we can reproduce the test environment.

### Test Configuration:
- Unity Version: [e.g. Unity 2020.2.0f1]
Expand Down
14 changes: 7 additions & 7 deletions CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# Contribution Guidelines

Thank you for your interest in contributing to Unity Robotics! To facilitate your
contributions, we've outlined a brief set of guidelines to ensure that your extensions
Thank you for your interest in contributing to Unity Robotics! To facilitate your
contributions, we've outlined a brief set of guidelines to ensure that your extensions
can be easily integrated.

## Communication
Expand Down Expand Up @@ -40,10 +40,10 @@ We run continuous integration on all PRs; all tests must be passing before the P

All Python code should follow the [PEP 8 style guidelines](https://pep8.org/).

All C# code should follow the [Microsoft C# Coding Conventions](https://docs.microsoft.com/en-us/dotnet/csharp/programming-guide/inside-a-program/coding-conventions).
Additionally, the [Unity Coding package](https://docs.unity3d.com/Packages/[email protected]/manual/index.html)
can be used to format, encode, and lint your code according to the standard Unity
development conventions. Be aware that these Unity conventions will supersede the
All C# code should follow the [Microsoft C# Coding Conventions](https://docs.microsoft.com/en-us/dotnet/csharp/programming-guide/inside-a-program/coding-conventions).
Additionally, the [Unity Coding package](https://docs.unity3d.com/Packages/[email protected]/manual/index.html)
can be used to format, encode, and lint your code according to the standard Unity
development conventions. Be aware that these Unity conventions will supersede the
Microsoft C# Coding Conventions where applicable.

Please note that even if the code you are changing does not adhere to these guidelines,
Expand All @@ -60,5 +60,5 @@ email us at [[email protected]](mailto:[email protected]).

## Contribution review

Once you have a change ready following the above ground rules, simply make a
Once you have a change ready following the above ground rules, simply make a
pull request in GitHub.
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,16 +10,16 @@ Instructions and examples on how to use this ROS package can be found on the [Un

## Community and Feedback

The Unity Robotics projects are open-source and we encourage and welcome contributions.
If you wish to contribute, be sure to review our [contribution guidelines](CONTRIBUTING.md)
The Unity Robotics projects are open-source and we encourage and welcome contributions.
If you wish to contribute, be sure to review our [contribution guidelines](CONTRIBUTING.md)
and [code of conduct](CODE_OF_CONDUCT.md).

## Support
For questions or discussions about Unity Robotics package installations or how to best set up and integrate your robotics projects, please create a new thread on the [Unity Robotics forum](https://forum.unity.com/forums/robotics.623/) and make sure to include as much detail as possible.

For feature requests, bugs, or other issues, please file a [GitHub issue](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/issues) using the provided templates and the Robotics team will investigate as soon as possible.

For any other questions or feedback, connect directly with the
For any other questions or feedback, connect directly with the
Robotics team at [[email protected]](mailto:[email protected]).

## License
Expand Down
4 changes: 3 additions & 1 deletion config/params.yaml
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
ROS_IP: 127.0.0.1
ROS_IP: 0.0.0.0
ROS_TCP_PORT: 10000

57 changes: 34 additions & 23 deletions src/ros_tcp_endpoint/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ class ClientThread(threading.Thread):
Thread class to read all data from a connection and pass along the data to the
desired source.
"""

def __init__(self, conn, tcp_server, incoming_ip, incoming_port):
"""
Set class variables
Expand Down Expand Up @@ -65,7 +66,7 @@ def read_int32(conn):
"""
raw_bytes = ClientThread.recvall(conn, 4)
num = struct.unpack('<I', raw_bytes)[0]
num = struct.unpack("<I", raw_bytes)[0]
return num

@staticmethod
Expand All @@ -81,7 +82,7 @@ def read_string(conn):
str_len = ClientThread.read_int32(conn)

str_bytes = ClientThread.recvall(conn, str_len)
decoded_str = str_bytes.decode('utf-8')
decoded_str = str_bytes.decode("utf-8")

return decoded_str

Expand All @@ -91,7 +92,7 @@ def read_message(conn):
Decode destination and full message size from socket connection.
Grab bytes in chunks until full message has been read.
"""
data = b''
data = b""

destination = ClientThread.read_string(conn)
full_message_size = ClientThread.read_int32(conn)
Expand Down Expand Up @@ -125,9 +126,9 @@ def serialize_message(destination, message):
Returns:
serialized destination and message as a list of bytes
"""
dest_bytes = destination.encode('utf-8')
dest_bytes = destination.encode("utf-8")
length = len(dest_bytes)
dest_info = struct.pack('<I%ss' % length, length, dest_bytes)
dest_info = struct.pack("<I%ss" % length, length, dest_bytes)

serial_response = BytesIO()
message.serialize(serial_response)
Expand All @@ -139,7 +140,7 @@ def serialize_message(destination, message):
# SEEK_END or 2 - end of the stream; offset is usually negative
response_len = serial_response.seek(0, 2)

msg_length = struct.pack('<I', response_len)
msg_length = struct.pack("<I", response_len)
serialized_message = dest_info + msg_length + serial_response.getvalue()

return serialized_message
Expand All @@ -166,52 +167,62 @@ def run(self):
while not halt_event.is_set():
destination, data = self.read_message(self.conn)

if destination == '':
#ignore this keepalive message, listen for more
if destination == "":
# ignore this keepalive message, listen for more
pass
elif destination == '__syscommand':
#handle a system command, such as registering new topics
elif destination == "__syscommand":
# handle a system command, such as registering new topics
self.tcp_server.handle_syscommand(data)
elif destination == '__srv':
elif destination == "__srv":
# handle a ros service message request, or a unity service message response
srv_message = RosUnitySrvMessage().deserialize(data)
if not srv_message.is_request:
self.tcp_server.send_unity_service_response(srv_message.srv_id, srv_message.payload)
self.tcp_server.send_unity_service_response(
srv_message.srv_id, srv_message.payload
)
continue
elif srv_message.topic == '__topic_list':
elif srv_message.topic == "__topic_list":
response = self.tcp_server.topic_list(data)
elif srv_message.topic not in self.tcp_server.source_destination_dict.keys():
error_msg = "Service destination '{}' is not registered! Known topics are: {} "\
.format(srv_message.topic, self.tcp_server.source_destination_dict.keys())
error_msg = "Service destination '{}' is not registered! Known topics are: {} ".format(
srv_message.topic, self.tcp_server.source_destination_dict.keys()
)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
# TODO: send a response to Unity anyway?
continue
continue
else:
ros_communicator = self.tcp_server.source_destination_dict[srv_message.topic]
ros_communicator = self.tcp_server.source_destination_dict[
srv_message.topic
]
response = ros_communicator.send(srv_message.payload)
if not response:
error_msg = "No response data from service '{}'!".format(srv_message.topic)
error_msg = "No response data from service '{}'!".format(
srv_message.topic
)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
# TODO: send a response to Unity anyway?
continue

serial_response = BytesIO()
response.serialize(serial_response)
response_message = RosUnitySrvMessage(srv_message.srv_id, False, '', serial_response.getvalue())
response_message = RosUnitySrvMessage(
srv_message.srv_id, False, "", serial_response.getvalue()
)
self.tcp_server.unity_tcp_sender.send_unity_message("__srv", response_message)
elif destination in self.tcp_server.source_destination_dict:
ros_communicator = self.tcp_server.source_destination_dict[destination]
response = ros_communicator.send(data)
else:
error_msg = "Topic '{}' is not registered! Known topics are: {} "\
.format(destination, self.tcp_server.source_destination_dict.keys())
error_msg = "Topic '{}' is not registered! Known topics are: {} ".format(
destination, self.tcp_server.source_destination_dict.keys()
)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
except IOError as e:
rospy.logerr("Exception: {}".format(e))
finally:
halt_event.set()
self.conn.close()
rospy.loginfo("Disconnected from {}".format(self.incoming_ip));
rospy.loginfo("Disconnected from {}".format(self.incoming_ip))
4 changes: 2 additions & 2 deletions src/ros_tcp_endpoint/publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ def __init__(self, topic, message_class, queue_size=10):
queue_size: Max number of entries to maintain in an outgoing queue
"""
RosSender.__init__(self)
self.msg = message_class()
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size)
self.msg = message_class
self.pub = rospy.Publisher(topic, self.msg, queue_size=queue_size)

def send(self, data):
"""
Expand Down
77 changes: 56 additions & 21 deletions src/ros_tcp_endpoint/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
from ros_tcp_endpoint.msg import RosUnitySysCommand
from ros_tcp_endpoint.srv import RosUnityTopicListResponse


class TcpServer:
"""
Initializes ROS node and TCP server.
Expand Down Expand Up @@ -71,8 +72,8 @@ def start(self, source_destination_dict=None):

def listen_loop(self):
"""
Creates and binds sockets using TCP variables then listens for incoming connections.
For each new connection a client thread will be created to handle communication.
Creates and binds sockets using TCP variables then listens for incoming connections.
For each new connection a client thread will be created to handle communication.
"""
rospy.loginfo("Starting server on {}:{}".format(self.tcp_ip, self.tcp_port))
tcp_server = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
Expand Down Expand Up @@ -107,7 +108,9 @@ def handle_syscommand(self, data):
message = RosUnitySysCommand().deserialize(data)
function = getattr(self.syscommands, message.command)
if function is None:
self.send_unity_error("Don't understand SysCommand.'{}'({})".format(message.command, message.params_json))
self.send_unity_error(
"Don't understand SysCommand.'{}'({})".format(message.command, message.params_json)
)
return
else:
params = json.loads(message.params_json)
Expand All @@ -119,50 +122,71 @@ def __init__(self, tcp_server):
self.tcp_server = tcp_server

def subscribe(self, topic, message_name):
if topic == '':
if topic == "":
self.tcp_server.send_unity_error(
"Can't subscribe to a blank topic name! SysCommand.subscribe({}, {})".format(topic, message_name))
"Can't subscribe to a blank topic name! SysCommand.subscribe({}, {})".format(
topic, message_name
)
)
return

message_class = resolve_message_name(message_name)
if message_class is None:
self.tcp_server.send_unity_error("SysCommand.subscribe - Unknown message class '{}'".format(message_name))
self.tcp_server.send_unity_error(
"SysCommand.subscribe - Unknown message class '{}'".format(message_name)
)
return

rospy.loginfo("RegisterSubscriber({}, {}) OK".format(topic, message_class))

if topic in self.tcp_server.source_destination_dict:
self.tcp_server.source_destination_dict[topic].unregister()

self.tcp_server.source_destination_dict[topic] = RosSubscriber(topic, message_class, self.tcp_server)
self.tcp_server.source_destination_dict[topic] = RosSubscriber(
topic, message_class, self.tcp_server
)

def publish(self, topic, message_name):
if topic == '':
if topic == "":
self.tcp_server.send_unity_error(
"Can't publish to a blank topic name! SysCommand.publish({}, {})".format(topic, message_name))
"Can't publish to a blank topic name! SysCommand.publish({}, {})".format(
topic, message_name
)
)
return

message_class = resolve_message_name(message_name)
if message_class is None:
self.tcp_server.send_unity_error("SysCommand.publish - Unknown message class '{}'".format(message_name))
self.tcp_server.send_unity_error(
"SysCommand.publish - Unknown message class '{}'".format(message_name)
)
return

rospy.loginfo("RegisterPublisher({}, {}) OK".format(topic, message_class))

if topic in self.tcp_server.source_destination_dict:
self.tcp_server.source_destination_dict[topic].unregister()

self.tcp_server.source_destination_dict[topic] = RosPublisher(topic, message_class, queue_size=10)
self.tcp_server.source_destination_dict[topic] = RosPublisher(
topic, message_class, queue_size=10
)

def ros_service(self, topic, message_name):
if topic == '':
if topic == "":
self.tcp_server.send_unity_error(
"RegisterRosService({}, {}) - Can't register a blank topic name!".format(topic, message_name))
"RegisterRosService({}, {}) - Can't register a blank topic name!".format(
topic, message_name
)
)
return

message_class = resolve_message_name(message_name, "srv")
if message_class is None:
self.tcp_server.send_unity_error("RegisterRosService({}, {}) - Unknown service class '{}'".format(topic, message_name, message_name))
self.tcp_server.send_unity_error(
"RegisterRosService({}, {}) - Unknown service class '{}'".format(
topic, message_name, message_name
)
)
return

rospy.loginfo("RegisterRosService({}, {}) OK".format(topic, message_class))
Expand All @@ -171,29 +195,38 @@ def ros_service(self, topic, message_name):
self.tcp_server.source_destination_dict[topic].unregister()

self.tcp_server.source_destination_dict[topic] = RosService(topic, message_class)

def unity_service(self, topic, message_name):
if topic == '':
if topic == "":
self.tcp_server.send_unity_error(
"RegisterUnityService({}, {}) - Can't register a blank topic name!".format(topic, message_name))
"RegisterUnityService({}, {}) - Can't register a blank topic name!".format(
topic, message_name
)
)
return

message_class = resolve_message_name(message_name, "srv")
if message_class is None:
self.tcp_server.send_unity_error("RegisterUnityService({}, {}) - Unknown service class '{}'".format(topic, message_name, message_name))
self.tcp_server.send_unity_error(
"RegisterUnityService({}, {}) - Unknown service class '{}'".format(
topic, message_name, message_name
)
)
return

rospy.loginfo("RegisterUnityService({}, {}) OK".format(topic, message_class))

if topic in self.tcp_server.source_destination_dict:
self.tcp_server.source_destination_dict[topic].unregister()

self.tcp_server.source_destination_dict[topic] = UnityService(topic.encode('ascii'), message_class, self.tcp_server)
self.tcp_server.source_destination_dict[topic] = UnityService(
topic.encode("ascii"), message_class, self.tcp_server
)


def resolve_message_name(name, extension="msg"):
try:
names = name.split('/')
names = name.split("/")
module_name = names[0]
class_name = names[1]
importlib.import_module(module_name + "." + extension)
Expand All @@ -205,7 +238,9 @@ def resolve_message_name(name, extension="msg"):
rospy.logerr("Failed to resolve module {}.{}".format(module_name, extension))
module = getattr(module, class_name)
if module is None:
rospy.logerr("Failed to resolve module {}.{}.{}".format(module_name, extension, class_name))
rospy.logerr(
"Failed to resolve module {}.{}.{}".format(module_name, extension, class_name)
)
return module
except (IndexError, KeyError, AttributeError, ImportError) as e:
rospy.logerr("Failed to resolve message name: {}".format(e))
Expand Down
Loading

0 comments on commit 6db5d23

Please sign in to comment.