From d7015b655cffa005acf317d0cf579c84935efbf3 Mon Sep 17 00:00:00 2001 From: Sravan Balaji Date: Sun, 26 Apr 2020 23:09:16 -0400 Subject: [PATCH] Trash vs Recycling Co-authored-by: dwitcpa - Combine pip3 install commands in Dockerfile - Add positions for trash and recycling bins - Classification is now just trash vs recycling - Remove extra bins, so we only have 2 - Increase default time limit to 10 minutes --- docker_env/gear/Dockerfile | 7 +++--- .../src/rrrobot/src/rrrobot_node.cpp | 24 ++++++++----------- src/rrrobot_ws/world/gear.py | 10 ++++---- 3 files changed, 18 insertions(+), 23 deletions(-) diff --git a/docker_env/gear/Dockerfile b/docker_env/gear/Dockerfile index 7391995..47e828b 100644 --- a/docker_env/gear/Dockerfile +++ b/docker_env/gear/Dockerfile @@ -57,9 +57,8 @@ RUN pip3 install -U \ numpy \ torch \ torchvision \ - Pillow - -RUN pip3 install pyyaml -RUN pip3 install rospkg + Pillow \ + pyyaml \ + rospkg CMD ["/bin/bash"] diff --git a/src/rrrobot_ws/src/rrrobot/src/rrrobot_node.cpp b/src/rrrobot_ws/src/rrrobot/src/rrrobot_node.cpp index ecc9e1c..4a2931c 100644 --- a/src/rrrobot_ws/src/rrrobot/src/rrrobot_node.cpp +++ b/src/rrrobot_ws/src/rrrobot/src/rrrobot_node.cpp @@ -155,23 +155,19 @@ private: ros::ServiceClient conveyor_pub; ros::Publisher arm_destination_pub; + Position trash_bin = Position(-0.3, 0.383, 1); + Position recycle_bin = Position(-0.3, 1.15, 1); + Position destination(const std::string &type) const { Position pos; - float z = 1; - - if (type == "cardboard") - pos = Position(-0.3, -1.916, z); - else if (type == "glass") - pos = Position(-0.3, -1.15, z); - else if (type == "metal") - pos = Position(-0.3, -0.383, z); - else if (type == "paper") - pos = Position(-0.3, 0.383, z); - else if (type == "plastic") - pos = Position(-0.3, 1.15, z); - else if (type == "trash") - pos = Position(-0.3, 1.916, z); + + if(type == "trash") { + pos = trash_bin; + } + else { + pos = recycle_bin; + } return pos; } diff --git a/src/rrrobot_ws/world/gear.py b/src/rrrobot_ws/world/gear.py index bb4fcd6..29a73ce 100644 --- a/src/rrrobot_ws/world/gear.py +++ b/src/rrrobot_ws/world/gear.py @@ -113,12 +113,12 @@ bin_depth = 0.6 bin_height = 0.72 bin_angle = 0.0 default_bin_origins = { - 'bin1': [-0.3, -1.916, 0], - 'bin2': [-0.3, -1.15, 0], - 'bin3': [-0.3, -0.383, 0], + # 'bin1': [-0.3, -1.916, 0], + # 'bin2': [-0.3, -1.15, 0], + # 'bin3': [-0.3, -0.383, 0], 'bin4': [-0.3, 0.383, 0], 'bin5': [-0.3, 1.15, 0], - 'bin6': [-0.3, 1.916, 0], + # 'bin6': [-0.3, 1.916, 0], } configurable_options = { @@ -135,7 +135,7 @@ configurable_options = { 'visualize_sensor_views': False, 'visualize_drop_regions': False, } -default_time_limit = 500 # seconds +default_time_limit = 600 # seconds max_count_per_model = 30 # limit on the number of instances of each model type def initialize_model_id_mappings(random_seed=None):