Skip to content

Commit

Permalink
Adding orbecc camera to launch options (#52)
Browse files Browse the repository at this point in the history
* Adding orbecc camera to launch options

Signed-off-by: Steve Macenski <[email protected]>

* linting

* linting

* adding docs

* finish

---------

Signed-off-by: Steve Macenski <[email protected]>
  • Loading branch information
SteveMacenski authored Aug 13, 2024
1 parent c86695c commit 43c6da3
Show file tree
Hide file tree
Showing 6 changed files with 263 additions and 7 deletions.
8 changes: 7 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ This project has demonstrations and analysis using AMD's powerful Ryzen CPU, AI,
These demonstrations orbit around the Honeybee reference platform, a [Clearpath Robotics Jackal](https://clearpathrobotics.com/jackal-small-unmanned-ground-vehicle/) outfitted with:
- AMD Ryzen Zen4 CPU using a [Miniforum UM790 Pro](https://store.minisforum.com/products/minisforum-um790-pro)
- [Ouster OS0-32](https://ouster.com/products/hardware/os0-lidar-sensor)
- [Realsense D435i](https://www.intelrealsense.com/depth-camera-d435i/)
- [Realsense D435i](https://www.intelrealsense.com/depth-camera-d435i/) or [Orbecc Gemini 355](https://www.orbbec.com/products/stereo-vision-camera/gemini-335/)
- [Microstrain GX-25](https://www.microstrain.com/inertial-sensors/3dm-gx5-25)

[Demonstration 1: Outdoor GPS Navigation](./honeybee_demos/honeybee_demos/gps_patrol_demo.py) | [Demonstration 2: Urban 3D Navigation](./honeybee_demos/honeybee_demos/urban_navigation_demo.py)
Expand Down Expand Up @@ -81,6 +81,10 @@ sudo apt install python3-vcstool # if don't already have
vcs import . < opennav_amd_demonstrations/deps.repos
cd ouster-lidar/ouster-ros && git submodule update --init
cd ../../../
# For Orbecc 335 cameras, if used instead of Realsense D435
sudo bash src/orbbec/OrbbecSDK_ROS2/orbbec_camera/scripts/install_udev_rules.sh
sudo udevadm control --reload-rules && sudo udevadm trigger
```

Next, we need to obtain our dependencies that are available from `rosdep`:
Expand Down Expand Up @@ -119,3 +123,5 @@ Data from the experiments are recorded and logged by the `nav2_watchdogs` in the
Note: each robot has a `colcon_ws` setup by Clearpath and is a hardcoded path with their auto-generation scripts. It is recommended to not touch this directory to allow for a complete rollback to on-delivery state should issues occur requiring Clearpath's intervention.

Subscribing to large topics over Wifi can hose the network and stall the programs. This can cause the robot to lose scheduling/TF transform timing, bluetooth controller to cutout, and so forth. It is recommended to use the robot in `ROS_LOCALHOST_ONLY` mode or not subscribe to topics off of the robot when not necessary or in current operations (i.e. close rviz so headless, run program in tmux session). This is good for setting up and debugging, but not in deployed applications -- at least with the default DDS settings in ROS 2 Humble. We also recommend using an isolated network for the robot so its not attempting to discover every device on a large corporate or building network (if not setting to localhost only).

Some configurations of Honeybee have the Realsense D435 and others have the Orbecc 355 cameras. If using Orbecc, set `USE_ORBECC=True` in your terminal before launching to bringup the Orbecc camera. This has been exported for you in the `~/.bashrc` and in the systemd bringup daemon for robots shipped from Open Navigation. If you wish to change cameras, simply install the new camera and adjust `USE_ORBECC` in `~/.bashrc` and `/etc/systemd/system/robot_bringup.service` as you desire.
4 changes: 4 additions & 0 deletions deps.repos
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@ repositories:
type: git
url: https://github.com/ouster-lidar/ouster-ros.git
version: ros2 # 2a0ef50f1dbe3f512321e809d6ca87391ce38f6e
orbbec/OrbbecSDK_ROS2:
type: git
url: https://github.com/orbbec/OrbbecSDK_ROS2
version: main

# For GPS demo
SteveMacenski/nonpersistent_voxel_layer:
Expand Down
2 changes: 2 additions & 0 deletions docs/setup_robot_automatic_bringup.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ Note: this relies on the workspace `amd_ws` in the root directory of the robot c

You can test this by powering off the computer and powering it back on. After the system is fully initialized, you should be able to see the system started up (i.e. see data with `ros2 topic list`, joystick your robot if you have setup to launch, etc).

Note, if you wish to set environmental variables, you may using `Environment="USE_ORBECC=true"` before `execStart`.

## Services provided

- `robot_bringup.service` brings up the robot's hardware
Expand Down
218 changes: 218 additions & 0 deletions honeybee_bringup/launch/include/orbecc.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,218 @@
# Copyright (c) 2024 Open Navigation LLC
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode


def convert_value(value):
if isinstance(value, str):
try:
return int(value)
except ValueError:
pass
try:
return float(value)
except ValueError:
pass
if value.lower() == 'true':
return True
elif value.lower() == 'false':
return False
return value


def load_parameters(context, args):
default_params = {arg.name: LaunchConfiguration(arg.name).perform(context) for arg in args}
return {
key: (convert_value(value))
for key, value in default_params.items()
}


def generate_launch_description():
args = [
DeclareLaunchArgument('depth_registration', default_value='true'),
DeclareLaunchArgument('serial_number', default_value=''),
DeclareLaunchArgument('usb_port', default_value=''),
DeclareLaunchArgument('device_num', default_value='1'),
DeclareLaunchArgument('point_cloud_qos', default_value='default'), # SENSOR_DATA
DeclareLaunchArgument('enable_point_cloud', default_value='True'),
DeclareLaunchArgument('enable_colored_point_cloud', default_value='false'),
DeclareLaunchArgument('connection_delay', default_value='10'),
DeclareLaunchArgument('color_width', default_value='424'),
DeclareLaunchArgument('color_height', default_value='240'),
DeclareLaunchArgument('color_fps', default_value='6'),
DeclareLaunchArgument('color_format', default_value='ANY'),
DeclareLaunchArgument('enable_color', default_value='true'),
DeclareLaunchArgument('color_qos', default_value='default'),
DeclareLaunchArgument('color_camera_info_qos', default_value='default'),
DeclareLaunchArgument('enable_color_auto_exposure', default_value='true'),
DeclareLaunchArgument('color_exposure', default_value='-1'),
DeclareLaunchArgument('color_gain', default_value='-1'),
DeclareLaunchArgument('enable_color_auto_white_balance', default_value='true'),
DeclareLaunchArgument('color_white_balance', default_value='-1'),
DeclareLaunchArgument('depth_width', default_value='424'),
DeclareLaunchArgument('depth_height', default_value='240'),
DeclareLaunchArgument('depth_fps', default_value='6'),
DeclareLaunchArgument('depth_format', default_value='ANY'),
DeclareLaunchArgument('enable_depth', default_value='true'),
DeclareLaunchArgument('depth_qos', default_value='default'),
DeclareLaunchArgument('depth_camera_info_qos', default_value='default'),
DeclareLaunchArgument('left_ir_width', default_value='0'),
DeclareLaunchArgument('left_ir_height', default_value='0'),
DeclareLaunchArgument('left_ir_fps', default_value='0'),
DeclareLaunchArgument('left_ir_format', default_value='ANY'),
DeclareLaunchArgument('enable_left_ir', default_value='false'),
DeclareLaunchArgument('left_ir_qos', default_value='default'),
DeclareLaunchArgument('left_ir_camera_info_qos', default_value='default'),
DeclareLaunchArgument('right_ir_width', default_value='0'),
DeclareLaunchArgument('right_ir_height', default_value='0'),
DeclareLaunchArgument('right_ir_fps', default_value='0'),
DeclareLaunchArgument('right_ir_format', default_value='ANY'),
DeclareLaunchArgument('enable_right_ir', default_value='false'),
DeclareLaunchArgument('right_ir_qos', default_value='default'),
DeclareLaunchArgument('right_ir_camera_info_qos', default_value='default'),
DeclareLaunchArgument('enable_ir_auto_exposure', default_value='true'),
DeclareLaunchArgument('ir_exposure', default_value='-1'),
DeclareLaunchArgument('ir_gain', default_value='-1'),
DeclareLaunchArgument('enable_sync_output_accel_gyro', default_value='false'),
DeclareLaunchArgument('enable_accel', default_value='false'),
DeclareLaunchArgument('accel_rate', default_value='200hz'),
DeclareLaunchArgument('accel_range', default_value='4g'),
DeclareLaunchArgument('enable_gyro', default_value='false'),
DeclareLaunchArgument('gyro_rate', default_value='200hz'),
DeclareLaunchArgument('gyro_range', default_value='1000dps'),
DeclareLaunchArgument('liner_accel_cov', default_value='0.01'),
DeclareLaunchArgument('angular_vel_cov', default_value='0.01'),
DeclareLaunchArgument('publish_tf', default_value='true'),
DeclareLaunchArgument('tf_publish_rate', default_value='0.0'),
DeclareLaunchArgument('ir_info_url', default_value=''),
DeclareLaunchArgument('color_info_url', default_value=''),
DeclareLaunchArgument('log_level', default_value='none'),
DeclareLaunchArgument('enable_publish_extrinsic', default_value='false'),
DeclareLaunchArgument('enable_d2c_viewer', default_value='false'),
DeclareLaunchArgument('enable_ldp', default_value='true'),
DeclareLaunchArgument('enable_soft_filter', default_value='true'),
DeclareLaunchArgument('soft_filter_max_diff', default_value='-1'),
DeclareLaunchArgument('soft_filter_speckle_size', default_value='-1'),
DeclareLaunchArgument('sync_mode', default_value='standalone'),
DeclareLaunchArgument('depth_delay_us', default_value='0'),
DeclareLaunchArgument('color_delay_us', default_value='0'),
DeclareLaunchArgument('trigger2image_delay_us', default_value='0'),
DeclareLaunchArgument('trigger_out_delay_us', default_value='0'),
DeclareLaunchArgument('trigger_out_enabled', default_value='true'),
DeclareLaunchArgument('frames_per_trigger', default_value='2'),
DeclareLaunchArgument('software_trigger_period', default_value='33'), # ms
DeclareLaunchArgument('enable_frame_sync', default_value='true'),
DeclareLaunchArgument('ordered_pc', default_value='false'),
DeclareLaunchArgument('use_hardware_time', default_value='true'),
DeclareLaunchArgument('enable_depth_scale', default_value='true'),
DeclareLaunchArgument('enable_decimation_filter', default_value='True'),
DeclareLaunchArgument('enable_hdr_merge', default_value='false'),
DeclareLaunchArgument('enable_sequence_id_filter', default_value='false'),
DeclareLaunchArgument('enable_threshold_filter', default_value='false'),
DeclareLaunchArgument('enable_noise_removal_filter', default_value='true'),
DeclareLaunchArgument('enable_spatial_filter', default_value='false'),
DeclareLaunchArgument('enable_temporal_filter', default_value='false'),
DeclareLaunchArgument('enable_hole_filling_filter', default_value='false'),
DeclareLaunchArgument('decimation_filter_scale_', default_value='6'),
DeclareLaunchArgument('sequence_id_filter_id', default_value='-1'),
DeclareLaunchArgument('threshold_filter_max', default_value='-1'),
DeclareLaunchArgument('threshold_filter_min', default_value='-1'),
DeclareLaunchArgument('noise_removal_filter_min_diff', default_value='256'),
DeclareLaunchArgument('noise_removal_filter_max_size', default_value='80'),
DeclareLaunchArgument('spatial_filter_alpha', default_value='-1.0'),
DeclareLaunchArgument('spatial_filter_diff_threshold', default_value='-1'),
DeclareLaunchArgument('spatial_filter_magnitude', default_value='-1'),
DeclareLaunchArgument('spatial_filter_radius', default_value='-1'),
DeclareLaunchArgument('temporal_filter_diff_threshold', default_value='-1.0'),
DeclareLaunchArgument('temporal_filter_weight', default_value='-1.0'),
DeclareLaunchArgument('hole_filling_filter_mode', default_value=''),
DeclareLaunchArgument('hdr_merge_exposure_1', default_value='-1'),
DeclareLaunchArgument('hdr_merge_gain_1', default_value='-1'),
DeclareLaunchArgument('hdr_merge_exposure_2', default_value='-1'),
DeclareLaunchArgument('hdr_merge_gain_2', default_value='-1'),
DeclareLaunchArgument('align_mode', default_value='SW'),
DeclareLaunchArgument('diagnostic_period', default_value='1.0'),
DeclareLaunchArgument('enable_laser', default_value='true'),
DeclareLaunchArgument('depth_precision', default_value=''),
DeclareLaunchArgument('device_preset', default_value='Default'),
DeclareLaunchArgument('laser_on_off_mode', default_value='0'),
DeclareLaunchArgument('retry_on_usb3_detection_failure', default_value='false'),
DeclareLaunchArgument('laser_energy_level', default_value='-1'),
DeclareLaunchArgument('enable_3d_reconstruction_mode', default_value='false'),
DeclareLaunchArgument('enable_sync_host_time', default_value='true'),
DeclareLaunchArgument('time_domain', default_value='device'),
DeclareLaunchArgument('enable_color_undistortion', default_value='false'),
DeclareLaunchArgument('config_file_path', default_value=''),
DeclareLaunchArgument('enable_heartbeat', default_value='false'),
]

static_tf_bridge = Node(
name='camera_0_static_tf',
executable='static_transform_publisher',
package='tf2_ros',
output='screen',
arguments=['--frame-id', 'camera_0_link', '--child-frame-id', 'camera_link'],
)

def get_params(context, args):
return [load_parameters(context, args)]

def create_node_action(context, args):
params = get_params(context, args)
return [
ComposableNodeContainer(
name='camera_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='orbbec_camera',
plugin='orbbec_camera::OBCameraNodeDriver',
name='camera_0',
namespace='sensors/camera_0',
parameters=params,
remappings=[
# Color
('color/image_raw', '/sensors/camera_0/color/image'),
('color/image_raw/compressed', '/sensors/camera_0/color/compressed'),
('color/image_raw/compressedDepth',
'/sensors/camera_0/color/compressedDepth'),
('color/image_raw/theora', '/sensors/camera_0/color/theora'),
# Depth
('depth/image_raw', '/sensors/camera_0/depth/image'),
('depth/image_raw/compressed', '/sensors/camera_0/depth/compressed'),
('depth/image_raw/compressedDepth',
'/sensors/camera_0/depth/compressedDepth'),
('depth/image_raw/theora', '/sensors/camera_0/depth/theora'),
# Points
('depth/points', '/sensors/camera_0/points')
]
),
],
output='screen',
)
]

return LaunchDescription(
[static_tf_bridge] + args + [
OpaqueFunction(function=lambda context: create_node_action(context, args))
]
)
36 changes: 30 additions & 6 deletions honeybee_bringup/launch/sensors.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,22 +12,45 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution, PythonExpression
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
bringup_dir = FindPackageShare('honeybee_bringup')

launch_camera = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
bringup_dir, 'launch', 'include', 'realsense.launch.py'])]),
use_orbecc = LaunchConfiguration('use_orbecc')
use_orbecc_cmd = DeclareLaunchArgument(
'use_orbecc',
default_value=os.getenv('USE_ORBECC', 'false').lower(),
description='Set to true to launch the ORBECC configuration'
)

launch_camera = GroupAction([
# Realsense
IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
bringup_dir, 'launch', 'include', 'realsense.launch.py'])]),
condition=UnlessCondition(PythonExpression(["'", use_orbecc, "' == 'true'"]))
),

# Orbecc
IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
bringup_dir, 'launch', 'include', 'orbecc.launch.py'])]),
condition=IfCondition(PythonExpression(["'", use_orbecc, "' == 'true'"]))
),
])

launch_imu = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
Expand All @@ -41,6 +64,7 @@ def generate_launch_description():
)

ld = LaunchDescription()
ld.add_action(use_orbecc_cmd)
ld.add_action(launch_camera)
ld.add_action(launch_imu)
ld.add_action(launch_lidar)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
A method to easily parse system metrics & analze files for analytics
"""


def parseSystemMetrics(file):
data_dicts = []
with open(file, 'r') as file:
Expand All @@ -48,6 +49,7 @@ def parseSystemMetrics(file):
data_dicts.append(adict)
return data_dicts


def analyze_system_metrics():
# Obtain all the raw data from files
files_in_directory = os.listdir('.') # os.path.expanduser('~/experiment_files')
Expand Down

0 comments on commit 43c6da3

Please sign in to comment.