Package Metadata & CV Model Update

- Remove commented out code from rrrobot.yaml and change time_limit to 10 minutes
- Update dependencies in rrrobot package.xml
- Update ROS package version to 1.0.0
- Update CV model with better pre-trained model
This commit is contained in:
Sravan Balaji
2020-04-27 12:32:39 -04:00
parent 5db44689b4
commit 2b0cc7f396
5 changed files with 22 additions and 166 deletions

View File

@@ -10,154 +10,5 @@ options:
order_part3: pulley_part
visualize_drop_regions: false # Whether or not to visualize drop regions (world frame only)
time_limit: 500 # Maximum time allowed for the trial once started, in seconds
time_limit: 600 # Maximum time allowed for the trial once started, in seconds
random_seed: 1 # Seed for the pseudo random number generator (used to randomize model names)
# Orders to announce during the trial
# orders:
# order_0:
# announcement_condition: time # Announce the order base on elapsed time
# announcement_condition_value: 0 # Time in seconds to wait before announcing the order
# shipment_count: 1 # How many of the same shipment are in the order
# destinations: [agv1] # Which agv the shipments must be delivered to
# # If specified it must be a list the same length as the shipment count
# # allowed values: agv1, agv2, any
# products: # List of products required to be in the kit
# part_0:
# type: order_part1 # Type of model required
# pose:
# xyz: [0.1, -0.15, 0] # Position required in the tray frame
# rpy: [0, 0, 'pi/2'] # Orientation required in the tray frame
# part_1:
# type: order_part1
# pose:
# xyz: [-0.1, -0.15, 0]
# rpy: [0, 0, 'pi/2']
# part_2:
# type: order_part2
# pose:
# xyz: [0.1, 0.15, 0]
# rpy: [0, 0, 0]
# part_3:
# type: order_part2
# pose:
# xyz: [-0.1, 0.15, 0]
# rpy: [0, 0, 0]
# order_1:
# announcement_condition: wanted_products # Announce the order when the boxes contain products from this order
# announcement_condition_value: 2
# shipment_count: 1
# destinations: [any]
# products:
# part_0:
# type: order_part3
# pose:
# xyz: [0.12, -0.2, 0]
# rpy: ['pi', 0, 0]
# part_1:
# type: order_part3
# pose:
# xyz: [-0.12, -0.2, 0]
# rpy: [0, 'pi', 0]
# part_2:
# type: order_part1
# pose:
# xyz: [0.15, 0.15, 0]
# rpy: [0, 0, 0]
# part_3:
# type: order_part2
# pose:
# xyz: [-0.15, 0.15, 0]
# rpy: [0, 0, 0]
# part_4:
# type: order_part2
# pose:
# rpy: [0, 'pi', 0]
# # Individual products that will be reported as faulty
# faulty_products:
# - piston_rod_part_57 # The piston rod part in the bins with randomized ID of 57
# - piston_rod_part_45
# # Models to be inserted in the bins
# models_over_bins:
# bin1: # Name of the bin (bin1-bin6, as named in the environment simulation)
# models: # List of models to insert
# gear_part: # Type of model to insert
# xyz_start: [0.1, 0.1, 0] # Origin of the first model to insert
# xyz_end: [0.5, 0.5, 0] # Origin of the last model to insert
# rpy: [0, 0, 'pi/4'] # Orientation of all models to insert
# num_models_x: 3 # How many models to insert along the x dimension
# num_models_y: 5 # How many models to insert along the y dimension
# bin5:
# models:
# gasket_part:
# xyz_start: [0.1, 0.1, 0.0]
# xyz_end: [0.5, 0.5, 0.0]
# rpy: [0, 0, 'pi/4']
# num_models_x: 2
# num_models_y: 3
# bin6:
# models:
# piston_rod_part:
# xyz_start: [0.1, 0.1, 0.0]
# xyz_end: [0.5, 0.5, 0.0]
# rpy: [0, 0, 'pi/4']
# num_models_x: 3
# num_models_y: 3
# # Models to be spawned in particular reference frames
# models_to_spawn:
# bin2::link: # Name of the reference frame
# models: # List of models to spawn
# piston_rod_part_1: # An arbitrary unique name of the model (will be randomized)
# type: piston_rod_part # Type of model (must be installed locally)
# pose:
# xyz: [0.2, 0.2, 0.75] # Co-ordinates of the model origin in the specified reference frame
# rpy: [0, 0, '-pi/2'] # Roll, pitch, yaw of the model in the specified reference frame
# # Models to be spawned on the conveyor belt
# belt_models:
# pulley_part: # name of part model to spawn
# 1.0: # Time in seconds after trial starts to spawn it
# pose:
# xyz: [0.0, 0.0, 0.1] # Coordinates relative to the start of the container to spawn the part
# rpy: [0, 0, 'pi/2'] # Roll, pitch, yaw of the model
# disk_part:
# 5.0:
# pose:
# xyz: [0.0, 0.0, 0.1]
# rpy: [0, 0, 'pi/2']
# # Drops from the vacuum gripper to be triggered at particular locations
# drops:
# drop_regions:
# above_agv_1:
# frame: agv1::kit_tray_1 # Frame the drop region/destination is specified in
# min: # Min corner of the bounding box that triggers a drop
# xyz: [-0.3, -0.3, 0.0]
# max: # Max corner of the bounding box that triggers a drop
# xyz: [0.3, 03, 0.5]
# destination: # Where to drop the part to
# xyz: [-0.35, 0.1, 0.15]
# rpy: [0, 0, 0.2]
# product_type_to_drop: gear_part
# above_agv_2:
# frame: agv2::kit_tray_2
# min:
# xyz: [-0.3, -0.3, 0.0]
# max:
# xyz: [0.3, 0.3, 0.5]
# destination:
# xyz: [0.15, 0.15, 0.15]
# rpy: [0, 0, -0.2]
# product_type_to_drop: pulley_part
# bin5_reachable:
# min:
# xyz: [0.0, 0.7, 0.7]
# max:
# xyz: [0.2, 1.60, 1.3]
# destination:
# xyz: [0.65, 1.15, 0.76]
# rpy: [0, 0, 0.5]
# product_type_to_drop: gasket_part

View File

@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>rrrobot</name>
<version>0.1.0</version>
<version>1.0.0</version>
<description>RRRobot package</description>
<maintainer email="balajsra@umich.edu">Sravan Balaji</maintainer>
<maintainer email="chenxgu@umich.edu">Chenxi Gu</maintainer>
@@ -16,12 +16,17 @@
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>std_srvs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>trajectory_msgs</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>gazebo_ros</depend>
<depend>message_generation</depend>
<depend>pcl_ros</depend>
<depend>pcl_conversion</depend>
<depend>gazebo</depend>
<depend>PCL</depend>
<depend>Eigen3</depend>
<depend>orocos_kdl</depend>
<exec_depend>message_runtime</exec_depend>
</package>

View File

@@ -8,19 +8,17 @@ from torch import nn
from PIL import Image
class Model_v1(nn.Module):
class Model_mobilenet(nn.Module):
def __init__(self):
super(Model_v1, self).__init__()
self.resnet = torchvision.models.resnet34(pretrained=True)
self.resnet.fc = torch.nn.Linear(512, 512)
self.addition = nn.Sequential(
nn.BatchNorm1d(512),
nn.Dropout(p=0.5),
nn.Linear(512, 6))
super(Model_mobilenet, self).__init__()
self.mobilenet = torchvision.models.mobilenet_v2(pretrained=True)
self.mobilenet.classifier = nn.Sequential(
nn.Dropout(p=0.2, inplace=False),
nn.Linear(1280, 6, bias=True))
def forward(self, image):
z = self.resnet(image)
z = self.addition(z)
z = self.mobilenet(image)
return z
@@ -28,6 +26,8 @@ def call_back(filename):
# prepare input file
filename = filename.data
input_image = Image.open(filename)
if input_image.size[0] < input_image.size[1]:
input_image = input_image.transpose(Image.ROTATE_90)
input_image = input_image.resize((512, 384))
# print(input_image.size)
input_image = np.moveaxis(np.asarray(input_image), 2, 0).astype(np.float32)
@@ -57,7 +57,7 @@ def call_back(filename):
garbage_type = type_dict[predicted_label]
rospy.loginfo(filename + ':' + garbage_type)
pub.publish(filename + ':' + garbage_type)
rate.sleep()
# rate.sleep()
def listener():
@@ -69,10 +69,10 @@ def listener():
if __name__ == '__main__':
rospy.init_node('cv_node')
# prepare pretrained model
model = Model_v1()
model.load_state_dict(torch.load('v1_0.001.pt', map_location='cpu'))
model = Model_mobilenet()
model.load_state_dict(torch.load('pytorch_pretrain_model.pt', map_location='cpu'))
model = model.to('cpu')
model.eval()