mirror of
https://github.com/EECS-467-W20-RRRobot-Project/RRRobot.git
synced 2025-08-22 16:12:45 +00:00
Trash vs Recycling
Co-authored-by: dwitcpa <dwitcpa@umich.edu> - 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
This commit is contained in:
@@ -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"]
|
||||
|
@@ -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;
|
||||
}
|
||||
|
@@ -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):
|
||||
|
Reference in New Issue
Block a user