Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

reformat python code as "black" and fix import order #36

Merged
merged 1 commit into from
Oct 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
77 changes: 41 additions & 36 deletions launch/driver_composition.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,55 +15,60 @@
#
#


import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch.actions import DeclareLaunchArgument as LaunchArg
from launch.actions import OpaqueFunction
from ament_index_python.packages import get_package_share_directory
import os
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def launch_setup(context, *args, **kwargs):
"""Create composable node."""
cam_name = LaunchConfig('camera_name')
cam_name = LaunchConfig("camera_name")
cam_str = cam_name.perform(context)
pkg_name = 'metavision_driver'
pkg_name = "metavision_driver"
share_dir = get_package_share_directory(pkg_name)
trigger_config = os.path.join(share_dir, 'config', 'trigger_pins.yaml')
bias_config = os.path.join(share_dir, 'config', 'silky_ev_cam.bias')
trigger_config = os.path.join(share_dir, "config", "trigger_pins.yaml")
bias_config = os.path.join(share_dir, "config", "silky_ev_cam.bias")
container = ComposableNodeContainer(
name='metavision_driver_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='metavision_driver',
plugin='metavision_driver::DriverROS2',
name=cam_name,
parameters=[
trigger_config, # loads the whole file
{'use_multithreading': False,
'bias_file': bias_config,
'camerainfo_url': '',
'frame_id': '',
'event_message_time_threshold': 1.0e-3}],
remappings=[
('~/events', cam_str + '/events')],
extra_arguments=[{'use_intra_process_comms': True}],
)
],
output='screen',
name="metavision_driver_container",
namespace="",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[
ComposableNode(
package="metavision_driver",
plugin="metavision_driver::DriverROS2",
name=cam_name,
parameters=[
trigger_config, # loads the whole file
{
"use_multithreading": False,
"bias_file": bias_config,
"camerainfo_url": "",
"frame_id": "",
"event_message_time_threshold": 1.0e-3,
},
],
remappings=[("~/events", cam_str + "/events")],
extra_arguments=[{"use_intra_process_comms": True}],
)
],
output="screen",
)
return [container]


def generate_launch_description():
"""Create composable node by calling opaque function."""
return launch.LaunchDescription([
LaunchArg('camera_name', default_value=['event_camera'],
description='camera name'),
OpaqueFunction(function=launch_setup)
])
return launch.LaunchDescription(
[
LaunchArg("camera_name", default_value=["event_camera"], description="camera name"),
OpaqueFunction(function=launch_setup),
]
)
83 changes: 44 additions & 39 deletions launch/driver_node.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,57 +15,62 @@
#
#

import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch.actions import DeclareLaunchArgument as LaunchArg
from launch.actions import OpaqueFunction
from ament_index_python.packages import get_package_share_directory
import os
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch_ros.actions import Node


def launch_setup(context, *args, **kwargs):
"""Create simple node."""
cam_name = LaunchConfig('camera_name')
cam_name = LaunchConfig("camera_name")
cam_str = cam_name.perform(context)
pkg_name = 'metavision_driver'
pkg_name = "metavision_driver"
share_dir = get_package_share_directory(pkg_name)
trigger_config = os.path.join(share_dir, 'config', 'trigger_pins.yaml')
trigger_config = os.path.join(share_dir, "config", "trigger_pins.yaml")
# bias_config = os.path.join(share_dir, 'config', 'silky_ev_cam.bias')
node = Node(package='metavision_driver',
executable='driver_node',
output='screen',
# prefix=['xterm -e gdb -ex run --args'],
name=cam_name,
parameters=[
trigger_config, # loads the whole file
{'use_multithreading': False,
'statistics_print_interval': 2.0,
# 'bias_file': bias_config,
'camerainfo_url': '',
'frame_id': '',
'serial': LaunchConfig('serial'),
'erc_mode': 'enabled',
'erc_rate': 100000000,
# 'roi': [0, 0, 100, 100],
# valid: 'external', 'loopback', 'disabled'
'trigger_in_mode': 'external',
# valid: 'enabled', 'disabled'
'trigger_out_mode': 'enabled',
'trigger_out_period': 100000, # in usec
'trigger_duty_cycle': 0.5, # fraction high/low
'event_message_time_threshold': 1.0e-3}],
remappings=[
('~/events', cam_str + '/events')])
node = Node(
package="metavision_driver",
executable="driver_node",
output="screen",
# prefix=['xterm -e gdb -ex run --args'],
name=cam_name,
parameters=[
trigger_config, # loads the whole file
{
"use_multithreading": False,
"statistics_print_interval": 2.0,
# 'bias_file': bias_config,
"camerainfo_url": "",
"frame_id": "",
"serial": LaunchConfig("serial"),
"erc_mode": "enabled",
"erc_rate": 100000000,
# 'roi': [0, 0, 100, 100],
# valid: 'external', 'loopback', 'disabled'
"trigger_in_mode": "external",
# valid: 'enabled', 'disabled'
"trigger_out_mode": "enabled",
"trigger_out_period": 100000, # in usec
"trigger_duty_cycle": 0.5, # fraction high/low
"event_message_time_threshold": 1.0e-3,
},
],
remappings=[("~/events", cam_str + "/events")],
)
return [node]


def generate_launch_description():
"""Create simple node by calling opaque function."""
return launch.LaunchDescription([
LaunchArg('camera_name', default_value=['event_camera'],
description='camera name'),
LaunchArg('serial', default_value=[''],
description='serial number of camera'),
OpaqueFunction(function=launch_setup)
])
return launch.LaunchDescription(
[
LaunchArg("camera_name", default_value=["event_camera"], description="camera name"),
LaunchArg("serial", default_value=[""], description="serial number of camera"),
OpaqueFunction(function=launch_setup),
]
)
24 changes: 11 additions & 13 deletions launch/recorder_node.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,26 +16,24 @@
#

import launch
from launch_ros.actions import Node
from launch.actions import OpaqueFunction
from launch_ros.actions import Node


def launch_setup(context, *args, **kwargs):
"""Create simple node."""
node = Node(package='metavision_driver',
# prefix=['xterm -e gdb -ex run --args'],
executable='recorder_node',
output='screen',
name='recorder_node',
parameters=[{'topics': ['/event_camera/events', '/image'],
'base_name': 'events_'}],
remappings=[
('~/events', '/events')])
node = Node(
package="metavision_driver",
# prefix=['xterm -e gdb -ex run --args'],
executable="recorder_node",
output="screen",
name="recorder_node",
parameters=[{"topics": ["/event_camera/events", "/image"], "base_name": "events_"}],
remappings=[("~/events", "/events")],
)
return [node]


def generate_launch_description():
"""Create simple node by calling opaque function."""
return launch.LaunchDescription([
OpaqueFunction(function=launch_setup)
])
return launch.LaunchDescription([OpaqueFunction(function=launch_setup)])
96 changes: 50 additions & 46 deletions launch/recording_driver.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,63 +16,67 @@
#

import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch.actions import DeclareLaunchArgument as LaunchArg
from launch.actions import OpaqueFunction
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def launch_setup(context, *args, **kwargs):
"""Create composable node."""
cam_name = LaunchConfig('camera_name')
cam_name = LaunchConfig("camera_name")
cam_str = cam_name.perform(context)
container = ComposableNodeContainer(
name='metavision_driver_container',
namespace='',
package='rclcpp_components',
executable='component_container',
# prefix=['xterm -e gdb -ex run --args'],
composable_node_descriptions=[
ComposableNode(
package='metavision_driver',
plugin='metavision_driver::DriverROS2',
name=cam_name,
parameters=[
{'use_multithreading': False,
'statistics_print_interval': 2.0,
'camerainfo_url': '',
'frame_id': '',
'event_message_time_threshold': 1.0e-3}],
remappings=[
('~/events', cam_str + '/events')],
extra_arguments=[{'use_intra_process_comms': True}],
),
ComposableNode(
package='rosbag2_composable_recorder',
plugin='rosbag2_composable_recorder::ComposableRecorder',
name="recorder",
parameters=[{'topics': ['/event_camera/events'],
'bag_name': LaunchConfig('bag'),
'bag_prefix': LaunchConfig('bag_prefix')}],
remappings=[
('~/events', cam_str + '/events')],
extra_arguments=[{'use_intra_process_comms': True}],
)
],
output='screen',
name="metavision_driver_container",
namespace="",
package="rclcpp_components",
executable="component_container",
# prefix=['xterm -e gdb -ex run --args'],
composable_node_descriptions=[
ComposableNode(
package="metavision_driver",
plugin="metavision_driver::DriverROS2",
name=cam_name,
parameters=[
{
"use_multithreading": False,
"statistics_print_interval": 2.0,
"camerainfo_url": "",
"frame_id": "",
"event_message_time_threshold": 1.0e-3,
}
],
remappings=[("~/events", cam_str + "/events")],
extra_arguments=[{"use_intra_process_comms": True}],
),
ComposableNode(
package="rosbag2_composable_recorder",
plugin="rosbag2_composable_recorder::ComposableRecorder",
name="recorder",
parameters=[
{
"topics": ["/event_camera/events"],
"bag_name": LaunchConfig("bag"),
"bag_prefix": LaunchConfig("bag_prefix"),
}
],
remappings=[("~/events", cam_str + "/events")],
extra_arguments=[{"use_intra_process_comms": True}],
),
],
output="screen",
)
return [container]


def generate_launch_description():
"""Create composable node by calling opaque function."""
return launch.LaunchDescription([
LaunchArg('camera_name', default_value=['event_camera'],
description='camera name'),
LaunchArg('bag', default_value=[''],
description='name of output bag'),
LaunchArg('bag_prefix', default_value=['events_'],
description='prefix of output bag'),
OpaqueFunction(function=launch_setup)
])
return launch.LaunchDescription(
[
LaunchArg("camera_name", default_value=["event_camera"], description="camera name"),
LaunchArg("bag", default_value=[""], description="name of output bag"),
LaunchArg("bag_prefix", default_value=["events_"], description="prefix of output bag"),
OpaqueFunction(function=launch_setup),
]
)
Loading