Skip to content

Commit

Permalink
Merge pull request #52 from stonier/stonier/drop_termcolor
Browse files Browse the repository at this point in the history
[mock] drop termcolor dependency
  • Loading branch information
stonier committed Feb 3, 2019
2 parents 85b3a5b + de8f71d commit 2ffe18a
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 16 deletions.
2 changes: 0 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@
<doc_depend>python-sphinx-rtd-theme</doc_depend>
<doc_depend>python-catkin-pkg</doc_depend>
<doc_depend>python-rospkg</doc_depend>
<doc_depend>python-termcolor</doc_depend>
<doc_depend>python_qt_binding</doc_depend>
<doc_depend>py_trees</doc_depend>
<doc_depend>py_trees_msgs</doc_depend>
Expand All @@ -46,7 +45,6 @@
-->

<!-- mocking & simulation dependencies -->
<exec_depend>python-termcolor</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<!--
<exec_depend>dynamic_reconfigure</exec_depend>
Expand Down
10 changes: 5 additions & 5 deletions py_trees_ros/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,17 @@
# Imports
##############################################################################

from . import blackboard
from . import exceptions
# from . import blackboard
# from . import exceptions
from . import mock
from . import programs
from . import trees
from . import tutorials
# from . import trees
# from . import tutorials
from . import utilities

# from . import actions
# from . import battery
# from . import conversions
# from . import mock
# from . import subscribers
# from . import visitors

Expand Down
24 changes: 16 additions & 8 deletions py_trees_ros/mock/led_strip.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@
import argparse
import functools
import math
import py_trees.console as console
import py_trees_ros
import rclpy
import std_msgs.msg as std_msgs
import sys
import termcolor # TODO: replace this with py_trees.console
import threading
import uuid

Expand All @@ -50,8 +50,6 @@ class LEDStrip(object):
_pattern = '*'
_pattern_width = 60 # total width of the pattern to be output
_pattern_name_spacing = 4 # space between pattern and the name of the pattern
# map colour names in message to termcolor names
_valid_colours = {'red': 'red', 'green': 'green', 'yellow': 'yellow', 'blue': 'blue', 'purple': 'magenta', 'white': 'white'}

def __init__(self):
self.node = rclpy.create_node("led_strip")
Expand All @@ -63,7 +61,7 @@ def __init__(self):
self.display_publisher = self.node.create_publisher(
msg_type=std_msgs.String,
topic="~/display",
qos_profile = py_trees_ros.utilities.qos_profile_latched_topic()
qos_profile=py_trees_ros.utilities.qos_profile_latched_topic()
)
self.duration_sec = 3.0
self.last_text = ''
Expand Down Expand Up @@ -109,10 +107,19 @@ def generate_led_text(self, colour):
return ""
else:
text = self.get_display_string(self._pattern_width, label=colour)
return termcolor.colored(text,
colour,
attrs=['blink']
)

# map colour names in message to console colour escape sequences
console_colour_map = {
'red': console.red,
'green': console.green,
'yellow': console.yellow,
'blue': console.blue,
'purple': console.magenta,
'white': console.white
}

coloured_text = console_colour_map[colour] + console.blink + text + console.reset
return coloured_text

def command_callback(self, msg):
with self.lock:
Expand Down Expand Up @@ -152,6 +159,7 @@ def spin(self):
pass
self.node.destroy_node()


def main():
"""
Entry point for the mock led strip.
Expand Down
5 changes: 4 additions & 1 deletion setup.cfg
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
[develop]
script-dir=$base/lib/py_trees_ros
[install]
install-scripts=$base/lib/py_trees_ros
install-scripts=$base/lib/py_trees_ros

[pep8]
max-line-length=299

0 comments on commit 2ffe18a

Please sign in to comment.