diff --git a/build-container/Dockerfile b/Dockerfile similarity index 100% rename from build-container/Dockerfile rename to Dockerfile diff --git a/README.md b/README.md index 42a840e..76da0dd 100644 --- a/README.md +++ b/README.md @@ -1,26 +1,8 @@ # Bento Boxes -**Containers for our robots!** - ---- - -**bento-box:** [bentorobotics/bento-box](https://hub.docker.com/r/bentorobotics/bento-box) - +**our robot container source** --- -**(auto)starting container** -> Container will automatically start on boot -```bash -cd - podman-compose up -``` - -**stopping/removing container** -```bash -cd - podman-compose down -``` - -> [!NOTE] -> podman-compose isn't directly packaged with podman; -> you may need to install `podman-compose` first +This repo contains the build files for our universal ROS container: [bentorobotics/rosbox](https://hub.docker.com/r/bentorobotics/rosbox) +Rosbox is best used with podman-compose, +to implement automatically starting robot software. diff --git a/bento-box/launch-content/.gitignore b/bento-box/launch-content/.gitignore deleted file mode 100644 index bee8a64..0000000 --- a/bento-box/launch-content/.gitignore +++ /dev/null @@ -1 +0,0 @@ -__pycache__ diff --git a/bento-box/launch-content/bento-box.launch.py b/bento-box/launch-content/bento-box.launch.py deleted file mode 100644 index cee084d..0000000 --- a/bento-box/launch-content/bento-box.launch.py +++ /dev/null @@ -1,67 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_path - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import Command, EnvironmentVariable, PathJoinSubstitution -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.substitutions import FindPackageShare - -from launch_ros.actions import Node -from launch_ros.parameter_descriptions import ParameterValue - -def generate_launch_description(): - return LaunchDescription([ - Node( - package='edu_robot', - executable='ethernet-gateway', - name='bento', - parameters=[PathJoinSubstitution(['./', 'parameters', 'bento-box.yaml'])], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento"), - # prefix=['gdbserver localhost:3000'], - output='screen' - ), - - IncludeLaunchDescription( - PythonLaunchDescriptionSource([ - PathJoinSubstitution([ - FindPackageShare('edu_robot'), - 'launch', - 'eduard-diagnostic.launch.py' - ]), - ]) - ), - - Node( - package='joy_linux', - executable='joy_linux_node', - parameters=[{'autorepeat_rate': 20.0}], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento") - ), - - Node( - package='edu_robot_control', - executable='remote_control', - parameters=[ PathJoinSubstitution(['./', 'parameters', 'bento_gamepad.yaml'])], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento") - ), - - Node( - package='usb_cam', - namespace='Driver', - executable='usb_cam_node_exe', - name='CAM', - parameters=[(PathJoinSubstitution(['./', 'parameters', 'Driver_Camera.yaml']))] - ), - - Node( - package='usb_cam', - namespace='CV', - executable='usb_cam_node_exe', - name='CAM', - parameters=[(PathJoinSubstitution(['./', 'parameters', 'CV_Camera.yaml']))] - ) - ]) - diff --git a/bento-box/launch-content/parameters/CV_Camera.yaml b/bento-box/launch-content/parameters/CV_Camera.yaml deleted file mode 100644 index 58376f8..0000000 --- a/bento-box/launch-content/parameters/CV_Camera.yaml +++ /dev/null @@ -1,22 +0,0 @@ -/**: - ros__parameters: - video_device: "/dev/v4l/by-path/platform-70090000.xusb-usb-0:2.3:1.0-video-index0" - framerate: 30.0 - io_method: "mmap" - frame_id: "camera" - pixel_format: "mjpeg2rgb" # see usb_cam/supported_formats for list of supported formats - image_width: 800 - image_height: 600 - camera_name: "CV" - #camera_info_url: "package://usb_cam/config/camera_info.yaml" - brightness: 200 - contrast: -1 - saturation: -1 - sharpness: -1 - gain: -1 - auto_white_balance: true - #white_balance: 4000 - autoexposure: false - exposure: 50 - #autofocus: false - focus: -1 diff --git a/bento-box/launch-content/parameters/Driver_Camera.yaml b/bento-box/launch-content/parameters/Driver_Camera.yaml deleted file mode 100644 index 9a5fa54..0000000 --- a/bento-box/launch-content/parameters/Driver_Camera.yaml +++ /dev/null @@ -1,22 +0,0 @@ -/**: - ros__parameters: - video_device: "/dev/v4l/by-path/platform-70090000.xusb-usb-0:2.1:1.0-video-index0" - framerate: 30.0 - io_method: "mmap" - frame_id: "camera" - pixel_format: "mjpeg2rgb" # see usb_cam/supported_formats for list of supported formats - image_width: 1024 #640 - image_height: 768 #480 - camera_name: "Driver" - #camera_info_url: "package://usb_cam/config/camera_info.yaml" - brightness: 150 - contrast: -1 - saturation: -1 - sharpness: -1 - gain: -1 - auto_white_balance: true - #white_balance: 4000 - autoexposure: false - exposure: 50 - autofocus: false - focus: -1 diff --git a/bento-box/launch-content/parameters/bento-box.yaml b/bento-box/launch-content/parameters/bento-box.yaml deleted file mode 100644 index 88cd377..0000000 --- a/bento-box/launch-content/parameters/bento-box.yaml +++ /dev/null @@ -1,101 +0,0 @@ -/**: - ros__parameters: - enable_collision_avoidance: true - tf_base_frame: base_link - tf_footprint_frame: base_footprint - use_sim_time: false - - imu: - fusion_weight: 0.005 - mounting_orientation: - pitch: 0.0 - roll: 0.0 - yaw: 0.0 - raw_data_mode: false - - motor_a: - closed_loop: true - control_frequency: 16000 - encoder_inverted: true - encoder_ratio: 2048.0 - gear_ratio: 44.0 - max_rpm: 204.5 - pid/kd: 0.0 - pid/ki: 40.0 - pid/kp: 0.5 - weight_low_pass_encoder: 0.8 - weight_low_pass_set_point: 0.8 - - motor_b: - closed_loop: true - control_frequency: 16000 - encoder_inverted: true - encoder_ratio: 2048.0 - gear_ratio: 44.0 - max_rpm: 204.5 - pid/kd: 0.0 - pid/ki: 40.0 - pid/kp: 0.5 - weight_low_pass_encoder: 0.8 - weight_low_pass_set_point: 0.8 - - motor_c: - closed_loop: true - control_frequency: 16000 - encoder_inverted: true - encoder_ratio: 2048.0 - gear_ratio: 44.0 - max_rpm: 204.5 - pid/kd: 0.0 - pid/ki: 40.0 - pid/kp: 0.5 - weight_low_pass_encoder: 0.8 - weight_low_pass_set_point: 0.8 - - motor_d: - closed_loop: true - control_frequency: 16000 - encoder_inverted: true - encoder_ratio: 2048.0 - gear_ratio: 44.0 - max_rpm: 204.5 - pid/kd: 0.0 - pid/ki: 40.0 - pid/kp: 0.5 - weight_low_pass_encoder: 0.8 - weight_low_pass_set_point: 0.8 - - range: - front: - left: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.01 - - right: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.01 - - rear: - left: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.01 - - right: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.01 - - skid: - length: - x: 0.25 - y: 0.32 - wheel_diameter: 0.17 - - mecanum: - length: - x: 0.25 - y: 0.36 - wheel_diameter: 0.1 diff --git a/bento-box/launch-content/parameters/bento_gamepad.yaml b/bento-box/launch-content/parameters/bento_gamepad.yaml deleted file mode 100644 index b1f5ed9..0000000 --- a/bento-box/launch-content/parameters/bento_gamepad.yaml +++ /dev/null @@ -1,24 +0,0 @@ -/**: - ros__parameters: - max_angular_velocity: 3.1415927410125732 - max_linear_velocity: 1.5 - use_sim_time: false - - joy_mapping: - axis: - forward: 1 - left: 0 - throttle: 5 - turn: 3 - - button: - disable: 3 - enable: 0 - indicate_operation: 7 - indicate_parking: 6 - indicate_turn_left: 4 - indicate_turn_right: 5 - indicate_warning: 8 - override_collision_avoidance: 7 - switch_to_mecanum_drive_kinematic: 2 - switch_to_skid_drive_kinematic: 1 diff --git a/bento-box/podman-compose.yaml b/bento-box/podman-compose.yaml deleted file mode 100644 index 8d5c7d6..0000000 --- a/bento-box/podman-compose.yaml +++ /dev/null @@ -1,21 +0,0 @@ -version: "3.0" - -services: - bento-box: - image: bentorobotics/rosbox:robot - container_name: bento-box-ros - user: root - restart: always - privileged: true - ipc: host - pid: host - mem_limit: 300mb - environment: - - EDU_ROBOT_NAMESPACE=bento - network_mode: "host" - volumes: - - './launch-content:/launch-content' - - '/dev:/dev' - devices: - - '/dev:/dev' - command: bash -c 'cd /launch-content; ros2 launch bento-box.launch.py' diff --git a/build-container/entrypoint.sh b/entrypoint.sh similarity index 100% rename from build-container/entrypoint.sh rename to entrypoint.sh diff --git a/build-container/makefile b/makefile similarity index 100% rename from build-container/makefile rename to makefile diff --git a/zyklop/launch-content/.gitignore b/zyklop/launch-content/.gitignore deleted file mode 100644 index bee8a64..0000000 --- a/zyklop/launch-content/.gitignore +++ /dev/null @@ -1 +0,0 @@ -__pycache__ diff --git a/zyklop/launch-content/parameters/Monocle_Camera.yaml b/zyklop/launch-content/parameters/Monocle_Camera.yaml deleted file mode 100644 index b3517a2..0000000 --- a/zyklop/launch-content/parameters/Monocle_Camera.yaml +++ /dev/null @@ -1,22 +0,0 @@ -/**: - ros__parameters: - video_device: "/dev/video0" - framerate: 30.0 - io_method: "mmap" - frame_id: "camera" - pixel_format: "mjpeg2rgb" # see usb_cam/supported_formats for list of supported formats - image_width: 320 - image_height: 240 - camera_name: "Monocle" - #camera_info_url: "package://usb_cam/config/camera_info.yaml" - brightness: 32 - contrast: -1 - saturation: -1 - sharpness: -1 - gain: -1 - auto_white_balance: true - #white_balance: 4000 - autoexposure: true - #exposure: 50 - autofocus: false - focus: -1 diff --git a/zyklop/launch-content/parameters/zyklop.yaml b/zyklop/launch-content/parameters/zyklop.yaml deleted file mode 100644 index 0e86bfa..0000000 --- a/zyklop/launch-content/parameters/zyklop.yaml +++ /dev/null @@ -1,72 +0,0 @@ -/**: - ros__parameters: -# General Parameters - tf_base_frame: base_link - tf_footprint_frame: base_footprint - use_sim_time: false - -# Collision Avoidance - collision_avoidance: - enable: false - distance_reduce_velocity: 0.6 - distance_velocity_zero: 0.05 - -# IMU Sensor - imu: - enable: false - fusion_weight: 0.029999999329447746 - raw_data_mode: false - -# Motor Controller - motor_d: - inverted: true - closed_loop: true - control_frequency: 16000 - encoder_inverted: true - encoder_ratio: 64.0 - gear_ratio: 70.0 - max_rpm: 150.0 - pid/kd: 0.0 - pid/ki: 120.0 - pid/kp: 0.5 - weight_low_pass_encoder: 0.3 - weight_low_pass_set_point: 0.2 - - - -# Range Sensor - range: - front: - left: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.009999999776482582 - - right: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.009999999776482582 - - rear: - left: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.009999999776482582 - - right: - field_of_view: 0.1745329201221466 - range_max: 5.0 - range_min: 0.009999999776482582 - -# Drive Kinematic - skid: - length: - x: 0.25 - y: 0.3199999928474426 - wheel_diameter: 0.17000000178813934 - - mecanum: - length: - x: 0.25 - y: 0.36000001430511475 - wheel_diameter: 0.10000000149011612 diff --git a/zyklop/launch-content/parameters/zyklop_gamepad.yaml b/zyklop/launch-content/parameters/zyklop_gamepad.yaml deleted file mode 100644 index 1d5d197..0000000 --- a/zyklop/launch-content/parameters/zyklop_gamepad.yaml +++ /dev/null @@ -1,24 +0,0 @@ -/**: - ros__parameters: - max_angular_velocity: 3.1415927410125732 - max_linear_velocity: 1.5 - use_sim_time: false - - joy_mapping: - axis: - forward: 1 - left: 0 - throttle: 4 - turn: 2 - - button: - disable: 0 - enable: 1 - indicate_operation: 7 - indicate_parking: 6 - indicate_turn_left: 4 - indicate_turn_right: 5 - indicate_warning: 8 - override_collision_avoidance: 7 - switch_to_mecanum_drive_kinematic: 3 - switch_to_skid_drive_kinematic: 2 diff --git a/zyklop/launch-content/zyklop.launch.py b/zyklop/launch-content/zyklop.launch.py deleted file mode 100644 index b45d6fa..0000000 --- a/zyklop/launch-content/zyklop.launch.py +++ /dev/null @@ -1,59 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_path - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import Command, EnvironmentVariable, PathJoinSubstitution -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.substitutions import FindPackageShare - -from launch_ros.actions import Node -from launch_ros.parameter_descriptions import ParameterValue - -def generate_launch_description(): - return LaunchDescription([ - Node( - package='edu_robot', - executable='iotbot-shield', - name='bento', - parameters=[PathJoinSubstitution(['./', 'parameters', 'zyklop.yaml'])], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento"), - # prefix=['gdbserver localhost:3000'], - output='screen' - ), - - IncludeLaunchDescription( - PythonLaunchDescriptionSource([ - PathJoinSubstitution([ - FindPackageShare('edu_robot'), - 'launch', - 'eduard-diagnostic.launch.py' - ]), - ]) - ), - - Node( - package='joy_linux', - executable='joy_linux_node', - parameters=[{'autorepeat_rate': 20.0}], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento") - ), - - Node( - package='edu_robot_control', - executable='remote_control', - parameters=[ PathJoinSubstitution(['./', 'parameters', 'zyklop_gamepad.yaml'])], - namespace=EnvironmentVariable('EDU_ROBOT_NAMESPACE', default_value="bento") - ), - - Node( - package='usb_cam', - namespace='Monocle', - executable='usb_cam_node_exe', - name='CAM', - parameters=[(PathJoinSubstitution(['./', 'parameters', 'Monocle_Camera.yaml']))] - ) - ]) - diff --git a/zyklop/podman-compose.yaml b/zyklop/podman-compose.yaml deleted file mode 100644 index 4459433..0000000 --- a/zyklop/podman-compose.yaml +++ /dev/null @@ -1,23 +0,0 @@ -version: "3.0" - -services: - bento-box: - image: bentorobotics/rosbox:robot - container_name: zyklop-ros - user: root - restart: always - privileged: true - ipc: host - pid: host - mem_limit: 300mb - environment: - - EDU_ROBOT_NAMESPACE=zyklop - network_mode: "host" - volumes: - - './launch-content:/launch-content' - - '/dev:/dev' - devices: - - '/dev:/dev' - group_add: - - dialout - command: bash -c 'cd /launch-content; ros2 launch zyklop.launch.py'