Skip to content

Commit

Permalink
Enable --no-daemon flag for some cli tools
Browse files Browse the repository at this point in the history
fixes #511
added daemon support to the other topic tools, except pub.

Signed-off-by: Dereck Wonnacott <dereck.wonnacott@havalus.com>
  • Loading branch information
US2 authored and dawonn-haval committed May 15, 2020
1 parent b622109 commit 7b5923d
Show file tree
Hide file tree
Showing 9 changed files with 35 additions and 12 deletions.
7 changes: 5 additions & 2 deletions ros2topic/ros2topic/verb/bw.py
Expand Up @@ -40,7 +40,8 @@

import rclpy
from rclpy.qos import qos_profile_sensor_data
from ros2cli.node.direct import DirectNode
from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import get_msg_class
from ros2topic.api import TopicNameCompleter
from ros2topic.verb import VerbExtension
Expand Down Expand Up @@ -74,6 +75,8 @@ class BwVerb(VerbExtension):
"""Display bandwidth used by topic."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic',
help='Topic name to monitor for bandwidth utilization')
Expand All @@ -85,7 +88,7 @@ def add_arguments(self, parser, cli_name):
f'(default: {DEFAULT_WINDOW_SIZE})', metavar='WINDOW')

def main(self, *, args):
with DirectNode(args) as node:
with NodeStrategy(args) as node:
_rostopic_bw(node.node, args.topic, window_size=args.window)


Expand Down
7 changes: 5 additions & 2 deletions ros2topic/ros2topic/verb/delay.py
Expand Up @@ -40,7 +40,8 @@

from rclpy.qos import qos_profile_sensor_data
from rclpy.time import Time
from ros2cli.node.direct import DirectNode
from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import get_msg_class
from ros2topic.api import TopicNameCompleter
from ros2topic.verb import VerbExtension
Expand All @@ -62,6 +63,8 @@ class DelayVerb(VerbExtension):
"""Display delay of topic from timestamp in header."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic',
help='Topic name to calculate the delay for')
Expand All @@ -77,7 +80,7 @@ def main(self, *, args):


def main(args):
with DirectNode(args) as node:
with NodeStrategy(args) as node:
_rostopic_delay(
node.node, args.topic, window_size=args.window)

Expand Down
9 changes: 7 additions & 2 deletions ros2topic/ros2topic/verb/echo.py
Expand Up @@ -22,6 +22,7 @@
from rclpy.node import Node
from rclpy.qos import QoSProfile
from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import add_qos_arguments_to_argument_parser
from ros2topic.api import get_msg_class
from ros2topic.api import qos_profile_from_short_keys
Expand Down Expand Up @@ -49,6 +50,8 @@ class EchoVerb(VerbExtension):
"""Output messages from a topic."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic_name',
help="Name of the ROS topic to listen to (e.g. '/chatter')")
Expand Down Expand Up @@ -92,7 +95,8 @@ def main(args):
args.qos_profile, reliability=args.qos_reliability, durability=args.qos_durability)
with NodeStrategy(args) as node:
if args.message_type is None:
message_type = get_msg_class(node, args.topic_name, include_hidden_topics=True)
message_type = get_msg_class(
node, args.topic_name, include_hidden_topics=True)
else:
message_type = get_message(args.message_type)
subscriber(
Expand Down Expand Up @@ -126,5 +130,6 @@ def cb(msg):
def subscriber_cb_csv(truncate_length, noarr, nostr):
def cb(msg):
nonlocal truncate_length, noarr, nostr
print(message_to_csv(msg, truncate_length=truncate_length, no_arr=noarr, no_str=nostr))
print(message_to_csv(msg, truncate_length=truncate_length,
no_arr=noarr, no_str=nostr))
return cb
3 changes: 3 additions & 0 deletions ros2topic/ros2topic/verb/find.py
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.

from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments

from ros2topic.api import get_topic_names_and_types
from ros2topic.api import message_type_completer
Expand All @@ -23,6 +24,8 @@ class FindVerb(VerbExtension):
"""Output a list of available topics of a given type."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic_type',
help="Name of the ROS topic type to filter for (e.g. 'std_msg/msg/String')")
Expand Down
7 changes: 5 additions & 2 deletions ros2topic/ros2topic/verb/hz.py
Expand Up @@ -45,7 +45,8 @@
from rclpy.clock import Clock
from rclpy.clock import ClockType
from rclpy.qos import qos_profile_sensor_data
from ros2cli.node.direct import DirectNode
from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import get_msg_class
from ros2topic.api import TopicNameCompleter
from ros2topic.verb import VerbExtension
Expand All @@ -67,6 +68,8 @@ class HzVerb(VerbExtension):
"""Print the average publishing rate to screen."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic_name',
help="Name of the ROS topic to listen to (e.g. '/chatter')")
Expand Down Expand Up @@ -102,7 +105,7 @@ def eval_fn(m):
else:
filter_expr = None

with DirectNode(args) as node:
with NodeStrategy(args) as node:
_rostopic_hz(node.node, topic, window_size=args.window_size, filter_expr=filter_expr,
use_wtime=args.use_wtime)

Expand Down
3 changes: 2 additions & 1 deletion ros2topic/ros2topic/verb/info.py
Expand Up @@ -13,7 +13,7 @@
# limitations under the License.

from ros2cli.node.strategy import NodeStrategy

from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import get_topic_names_and_types
from ros2topic.api import TopicNameCompleter
from ros2topic.verb import VerbExtension
Expand All @@ -23,6 +23,7 @@ class InfoVerb(VerbExtension):
"""Print information about a topic."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)
arg = parser.add_argument(
'topic_name',
help="Name of the ROS topic to get info (e.g. '/chatter')")
Expand Down
5 changes: 3 additions & 2 deletions ros2topic/ros2topic/verb/list.py
Expand Up @@ -12,8 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ros2cli.node.strategy import add_arguments
from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2topic.api import get_topic_names_and_types
from ros2topic.verb import VerbExtension

Expand All @@ -22,7 +22,8 @@ class ListVerb(VerbExtension):
"""Output a list of available topics."""

def add_arguments(self, parser, cli_name):
add_arguments(parser)
add_strategy_node_arguments(parser)

parser.add_argument(
'-t', '--show-types', action='store_true',
help='Additionally show the topic type')
Expand Down
3 changes: 2 additions & 1 deletion ros2topic/ros2topic/verb/pub.py
Expand Up @@ -150,6 +150,7 @@ def timer_callback():
rclpy.spin_once(node)

if times == 1:
time.sleep(0.1) # make sure the message reaches the wire before exiting
# make sure the message reaches the wire before exiting
time.sleep(0.1)

node.destroy_timer(timer)
3 changes: 3 additions & 0 deletions ros2topic/ros2topic/verb/type.py
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.

from ros2cli.node.strategy import NodeStrategy
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments

from ros2topic.api import get_topic_names_and_types
from ros2topic.api import TopicNameCompleter
Expand All @@ -23,6 +24,8 @@ class TypeVerb(VerbExtension):
"""Print a topic's type."""

def add_arguments(self, parser, cli_name):
add_strategy_node_arguments(parser)

arg = parser.add_argument(
'topic_name',
help="Name of the ROS topic to get type (e.g. '/chatter')")
Expand Down

0 comments on commit 7b5923d

Please sign in to comment.