def test_hashable(): assert hash(Foo(xyz=1)) != hash(Bar(xyz=1)) assert hash(getdag(source1)) != hash(getdag(source2)) assert hash(getdag(consumer)) != hash(consumer.clone(foo=1)) assert hash(consumer.clone(foo=1)) == hash(consumer.clone(foo=1)) assert hash(getdag(consumer)) != hash(consumer.clone(stream=source2)) assert hash(consumer.clone(stream=source2)) == hash( consumer.clone(stream=source2)) assert hash(consumer.clone(stream=marv.select(source2, name='foo'))) != \ hash(consumer.clone(stream=marv.select(source2, name='bar'))) assert hash(consumer.clone(stream=marv.select(source2, name='foo'))) == \ hash(consumer.clone(stream=marv.select(source2, name='foo')))
def test(): @marv.node() def source(): yield # pragma: nocoverage @marv.node(Test, group='ondemand', version=1) @marv.input('foo', default=1) @marv.input('bar', type=int) @marv.input('baz', default=source) @marv.input('qux', foreach=marv.select(source, 'stream')) def consumer(foo, bar, baz, qux): yield # pragma: nocoverage node = consumer.__marv_node__ assert node.function == 'marv_api.tests.test_decorators.test.<locals>.consumer' assert node.inputs.__fields__.keys() == {'foo', 'bar', 'baz', 'qux'} assert node.inputs.__annotations__ == {'bar': int} assert node.inputs.foo == 1 assert node.inputs.bar == NOTSET assert node.inputs.baz == Stream(node=getdag(source)) assert node.inputs.qux == Stream(node=getdag(source), name='stream') assert node.message_schema == 'marv_api.tests.types_capnp:Test' assert node.group == 'ondemand' assert node.version == 1 assert node.foreach == 'qux'
def test_clone(): @marv.node() def source1(): yield # pragma: nocoverage @marv.node() def source2(): yield # pragma: nocoverage @marv.node() @marv.input('foo', default=1) @marv.input('stream', default=source1) def consumer(foo, stream): yield # pragma: nocoverage clone = consumer.clone(foo=10, stream=source2) assert clone.inputs.foo == 10 assert clone.inputs.stream == Stream(node=getdag(source2)) clone = consumer.clone(stream=marv.select(source2, 'foo')) assert clone.inputs.stream == Stream(node=getdag(source2), name='foo')
# Copyright 2016 - 2020 Ternaris. # SPDX-License-Identifier: Apache-2.0 """Image stream conversion nodes.""" import marv_api as marv from marv_robotics.bag import make_deserialize, messages from marv_ros.img_tools import ImageConversionError, ImageFormatError from marv_ros.img_tools import imgmsg_to_cv2 @marv.node() @marv.input('stream', marv.select(messages, '/kitti/camera_color_left/image_rawX')) def rosmsg_imgstream(stream): """Convert stream of raw ros messages into stream of deserialized messages.""" deserialize = make_deserialize(stream) fixme while True: msg = yield marv.pull(stream) if msg is None: break rosmsg = deserialize(msg.data) yield marv.push(rosmsg) @marv.node() @marv.input('stream', rosmsg_imgstream) def imgsrc(stream):
# Copyright 2016 - 2018 Ternaris. # SPDX-License-Identifier: AGPL-3.0-only from pkg_resources import resource_filename import marv_api as marv import marv_node.testing from marv_node.testing import make_dataset, run_nodes, temporary_directory from marv_robotics.bag import get_message_type, messages from marv_robotics.fulltext import fulltext from marv_store import Store @marv.node() @marv.input('chatter', default=marv.select(messages, '/chatter')) def collect(chatter): pytype = get_message_type(chatter) rosmsg = pytype() msg = yield marv.pull(chatter) assert msg is not None rosmsg.deserialize(msg.data) yield marv.push(rosmsg.data) while True: msg = yield marv.pull(chatter) if msg is None: return rosmsg.deserialize(msg.data) yield marv.push(rosmsg.data) class TestCase(marv_node.testing.TestCase):
import mpld3 import plotly.graph_objects as go import marv_api as marv from marv_detail.types_capnp import Section, Widget # pylint: disable=no-name-in-module from marv_nodes.types_capnp import File # pylint: disable=no-name-in-module from marv_robotics.bag import get_message_type, raw_messages from marv_ros.img_tools import imgmsg_to_cv2 TOPIC = '/wide_stereo/left/image_rect_throttle' # pylint: disable=redefined-outer-name @marv.node(File) @marv.input('cam', marv.select(raw_messages, TOPIC)) def image(cam): """Extract first image of input stream to jpg file. Args: cam: Input stream of raw rosbag messages. Returns: File instance for first image of input stream. """ # Set output stream title and pull first message yield marv.set_header(title=cam.topic) msg = yield marv.pull(cam) if msg is None: return
# Copyright 2016 - 2018 Ternaris. # SPDX-License-Identifier: AGPL-3.0-only import re import marv_api as marv from marv_api.types import Words from .bag import make_deserialize, messages WSNULL = re.compile(r'[\s\x00]') @marv.node(Words) @marv.input('stream', foreach=marv.select(messages, ('*:std_msgs/String,' '*:std_msgs/msg/String'))) def fulltext_per_topic(stream): yield marv.set_header(title=stream.topic) words = set() deserialize = make_deserialize(stream) while True: msg = yield marv.pull(stream) if msg is None: break rosmsg = deserialize(msg.data) words.update(WSNULL.split(rosmsg.data)) if not words: raise marv.Abort() yield marv.push({'words': list(words)})
import json import math from math import asin, cos, radians, sin, sqrt from pathlib import Path import numpy import utm import marv_api as marv from marv_api.types import Float64Value from marv_detail.types_capnp import Section # pylint: disable=no-name-in-module from marv_robotics.bag import make_deserialize, make_get_timestamp, messages @marv.node() @marv.input('stream', marv.select(messages, '*:sensor_msgs/NavSatFix')) # @marv.input('stream', marv.select(messages, '*:geometry_msgs/PoseStamped')) def motion_timestamp(stream): """Extract timestamps for motion events. Args: stream: ROS message stream with Pose or GPS messages. Yields: Message stream with timestamps. """ log = yield marv.get_logger() stream = yield marv.pull(stream) # take first matching connection if not stream: return
rot[0, 0] = 1 - 2 * q2 * q2 - 2 * q3 * q3 rot[0, 1] = 2 * (q1 * q2 - q3 * q4) rot[0, 2] = 2 * (q1 * q3 + q2 * q4) rot[1, 0] = 2 * (q1 * q2 + q3 * q4) rot[1, 1] = 1 - 2 * q1 * q1 - 2 * q3 * q3 rot[1, 2] = 2 * (q2 * q3 - q1 * q4) rot[2, 0] = 2 * (q1 * q3 - q2 * q4) rot[2, 1] = 2 * (q1 * q4 + q2 * q3) rot[2, 2] = 1 - 2 * q1 * q1 - 2 * q2 * q2 vec = np.dot(rot, [1, 0, 0]) return np.arctan2(vec[1], vec[0]) @marv.node() @marv.input('stream', foreach=marv.select(messages, ('*:sensor_msgs/NavSatFix,' '*:sensor_msgs/msg/NavSatFix'))) def positions(stream): yield marv.set_header(title=stream.topic) log = yield marv.get_logger() deserialize = make_deserialize(stream) get_timestamp = make_get_timestamp(log, stream) erroneous = 0 e_offset = None n_offset = None u_offset = None positions = [] while True: msg = yield marv.pull(stream) if msg is None: break
# Copyright 2016 - 2018 Ternaris. # SPDX-License-Identifier: AGPL-3.0-only import numpy as np import marv_api as marv from marv_api.types import GeoJson from .bag import make_deserialize, make_get_timestamp, messages @marv.node() @marv.input('stream', foreach=marv.select(messages, ('*:sensor_msgs/NavSatFix,' '*:sensor_msgs/msg/NavSatFix'))) def navsatfix(stream): yield marv.set_header(title=stream.topic) log = yield marv.get_logger() deserialize = make_deserialize(stream) get_timestamp = make_get_timestamp(log, stream) erroneous = 0 while True: msg = yield marv.pull(stream) if msg is None: break rosmsg = deserialize(msg.data) if not hasattr(rosmsg, 'status') or \ np.isnan(rosmsg.longitude) or \ np.isnan(rosmsg.latitude) or \ np.isnan(rosmsg.altitude):
if hasattr(msg, 'format'): return compressed_imgmsg_to_cv2(msg) if 'FC' in msg.encoding: passimg = numpy.nan_to_num(imgmsg_to_cv2(msg)) valscaled = cv2.convertScaleAbs(passimg, None, scale, offset) return valscaled mono = msg.encoding.startswith('mono') or msg.encoding[-1] in [ '1', 'U', 'S', 'F' ] return imgmsg_to_cv2(msg, 'mono8' if mono else 'bgr8') @marv.node(File, version=1) @marv.input('stream', foreach=marv.select(messages, IMAGE_MSG_TYPES)) @marv.input('speed', default=4) @marv.input('convert_32FC1_scale', default=1) @marv.input('convert_32FC1_offset', default=0) def ffmpeg(stream, speed, convert_32FC1_scale, convert_32FC1_offset): # pylint: disable=invalid-name """Create video for each sensor_msgs/Image topic with ffmpeg.""" # pylint: disable=too-many-locals yield marv.set_header(title=stream.topic) name = f"{stream.topic.replace('/', '_')[1:]}.webm" video = yield marv.make_file(name) duration = (stream.end_time - stream.start_time) * 1e-9 framerate = (stream.msg_count / duration) if duration else 1 deserialize = make_deserialize(stream) with ExitStack() as stack:
# Copyright 2016 - 2018 Ternaris. # SPDX-License-Identifier: AGPL-3.0-only from pkg_resources import resource_filename import marv_api as marv import marv_node.testing from marv_node.testing import make_dataset, run_nodes, temporary_directory from marv_robotics.bag import messages from marv_store import Store @marv.node() @marv.input('stream', default=marv.select(messages, '/non-existent')) def nooutput(stream): yield marv.set_header() while True: msg = yield marv.pull(stream) if msg is None: return yield marv.push(msg) @marv.node() @marv.input('nooutput', default=nooutput) @marv.input('chatter', default=marv.select(messages, '/chatter')) def collect(nooutput, chatter): # pylint: disable=redefined-outer-name msg = yield marv.pull(nooutput) assert msg is None msg = yield marv.pull(chatter) assert msg is not None