mirror of
https://github.com/EECS-467-W20-RRRobot-Project/RRRobot.git
synced 2025-04-20 21:35:22 +00:00
Merge branch 'GEAR_arm_controller' of github.com:EECS-467-W20-RRRobot-Project/RRRobot into GEAR_arm_controller
This commit is contained in:
commit
216cc3485f
@ -1,9 +1,4 @@
|
|||||||
sensors:
|
sensors:
|
||||||
logical_camera_1:
|
|
||||||
type: logical_camera
|
|
||||||
pose:
|
|
||||||
xyz: [1.2, 3.5, 1.5]
|
|
||||||
rpy: [0, 1.5707, 0]
|
|
||||||
depth_camera_1:
|
depth_camera_1:
|
||||||
type: depth_camera
|
type: depth_camera
|
||||||
pose:
|
pose:
|
||||||
|
@ -50,7 +50,7 @@ def call_back(filename):
|
|||||||
print('type: ', type_dict[predicted_label])
|
print('type: ', type_dict[predicted_label])
|
||||||
|
|
||||||
# publish a message, name of this node is 'cv_model'
|
# publish a message, name of this node is 'cv_model'
|
||||||
pub = rospy.Publisher('cv_model', String, queue_size=10)
|
pub = rospy.Publisher('/cv_model', String, queue_size=10)
|
||||||
# rospy.init_node('talker', anonymous=True)
|
# rospy.init_node('talker', anonymous=True)
|
||||||
rate = rospy.Rate(10) # 10hz
|
rate = rospy.Rate(10) # 10hz
|
||||||
|
|
||||||
|
@ -20,7 +20,7 @@ class ObjectSpawner
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
ObjectSpawner(const std::string &model_file = "/app/rrrobot_ws/src/gazebo_models/model_mappings.txt")
|
ObjectSpawner(const std::string &model_file = "/app/rrrobot_ws/src/gazebo_models/model_mappings.txt")
|
||||||
: DEFAULT_SPAWN_POINT(1.21825, 5.474367, 0.937978),
|
: DEFAULT_SPAWN_POINT(1.21825, 4.0, 0.937978),
|
||||||
CONVEYOR_WIDTH(0.391404)
|
CONVEYOR_WIDTH(0.391404)
|
||||||
{
|
{
|
||||||
// DEFAULT_SPAWN_POINT.x = 0.2516105;
|
// DEFAULT_SPAWN_POINT.x = 0.2516105;
|
||||||
|
@ -127,7 +127,7 @@ public:
|
|||||||
|
|
||||||
desired_grasp_pose = grasp_pose;
|
desired_grasp_pose = grasp_pose;
|
||||||
// TODO: Tune z offset so end effector doesn't hit object
|
// TODO: Tune z offset so end effector doesn't hit object
|
||||||
desired_grasp_pose.position.z -= 0.025;
|
desired_grasp_pose.position.z += 0.01;
|
||||||
|
|
||||||
if (current_robot_state & RobotState::WAITING_FOR_CLASSIFICATION)
|
if (current_robot_state & RobotState::WAITING_FOR_CLASSIFICATION)
|
||||||
{
|
{
|
||||||
@ -165,23 +165,19 @@ private:
|
|||||||
ros::ServiceClient conveyor_pub;
|
ros::ServiceClient conveyor_pub;
|
||||||
ros::Publisher arm_destination_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 destination(const std::string &type) const
|
||||||
{
|
{
|
||||||
Position pos;
|
Position pos;
|
||||||
float z = 1;
|
|
||||||
|
if(type == "trash") {
|
||||||
if (type == "cardboard")
|
pos = trash_bin;
|
||||||
pos = Position(-0.3, -1.916, z);
|
}
|
||||||
else if (type == "glass")
|
else {
|
||||||
pos = Position(-0.3, -1.15, z);
|
pos = recycle_bin;
|
||||||
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);
|
|
||||||
|
|
||||||
return pos;
|
return pos;
|
||||||
}
|
}
|
||||||
|
@ -113,12 +113,12 @@ bin_depth = 0.6
|
|||||||
bin_height = 0.72
|
bin_height = 0.72
|
||||||
bin_angle = 0.0
|
bin_angle = 0.0
|
||||||
default_bin_origins = {
|
default_bin_origins = {
|
||||||
'bin1': [-0.3, -1.916, 0],
|
# 'bin1': [-0.3, -1.916, 0],
|
||||||
'bin2': [-0.3, -1.15, 0],
|
# 'bin2': [-0.3, -1.15, 0],
|
||||||
'bin3': [-0.3, -0.383, 0],
|
# 'bin3': [-0.3, -0.383, 0],
|
||||||
'bin4': [-0.3, 0.383, 0],
|
'bin4': [-0.3, 0.383, 0],
|
||||||
'bin5': [-0.3, 1.15, 0],
|
'bin5': [-0.3, 1.15, 0],
|
||||||
'bin6': [-0.3, 1.916, 0],
|
# 'bin6': [-0.3, 1.916, 0],
|
||||||
}
|
}
|
||||||
|
|
||||||
configurable_options = {
|
configurable_options = {
|
||||||
@ -135,7 +135,7 @@ configurable_options = {
|
|||||||
'visualize_sensor_views': False,
|
'visualize_sensor_views': False,
|
||||||
'visualize_drop_regions': 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
|
max_count_per_model = 30 # limit on the number of instances of each model type
|
||||||
|
|
||||||
def initialize_model_id_mappings(random_seed=None):
|
def initialize_model_id_mappings(random_seed=None):
|
||||||
|
Loading…
x
Reference in New Issue
Block a user