Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Tiago robot, configs and examples #99

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion gibson2/envs/env_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
from gibson2.robots.freight_robot import Freight
from gibson2.robots.fetch_robot import Fetch
from gibson2.robots.locobot_robot import Locobot
from gibson2.robots.tiago_single_robot import Tiago_Single
from gibson2.robots.tiago_dual_robot import Tiago_Dual
from gibson2.simulator import Simulator
from gibson2.scenes.empty_scene import EmptyScene
from gibson2.scenes.stadium_scene import StadiumScene
Expand Down Expand Up @@ -174,6 +176,9 @@ def load(self):
if first_n != -1:
scene._set_first_n_objects(first_n)
self.simulator.import_ig_scene(scene)
else:
raise Exception(
'Unknown scene type: {}'.format(self.config['scene']))

if self.config['robot'] == 'Turtlebot':
robot = Turtlebot(self.config)
Expand All @@ -193,9 +198,13 @@ def load(self):
robot = Fetch(self.config)
elif self.config['robot'] == 'Locobot':
robot = Locobot(self.config)
elif self.config['robot'] == 'Tiago_Single':
robot = Tiago_Single(self.config)
elif self.config['robot'] == 'Tiago_Dual':
robot = Tiago_Dual(self.config)
else:
raise Exception(
'unknown robot type: {}'.format(self.config['robot']))
'Unknown robot type: {}'.format(self.config['robot']))

self.scene = scene
self.robots = [robot]
Expand Down
83 changes: 83 additions & 0 deletions gibson2/examples/configs/tiago_dual_point_nav.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
# scene
scene: gibson
scene_id: Rs
#scene: igibson
#scene_id: Rs_int
is_interactive: false
build_graph: true
load_texture: true
trav_map_resolution: 0.1
trav_map_erosion: 3

# robot
robot: Tiago_Dual
is_discrete: false
wheel_velocity: 1.0
torso_lift_velocity: 1.0
head_velocity: 0.8
arm_left_velocity: 0.9
arm_right_velocity: 0.9
gripper_velocity: 1.0
hand_velocity: 0.5

# task, observation and action
#task: pointgoal # pointgoal|objectgoal|areagoal|reaching
#target_dist_min: 1.0
#target_dist_max: 10.0
#initial_pos_z_offset: 0.1
#additional_states_dim: 4
task: point_nav_random
target_dist_min: 1.0
target_dist_max: 10.0
goal_format: polar
task_obs_dim: 4

# reward
reward_type: geodesic
success_reward: 10.0
slack_reward: -0.01
potential_reward_weight: 1.0
collision_reward_weight: -0.1
collision_ignore_link_a_ids: [0, 1, 2] # ignore collisions with these robot links

# discount factor
discount_factor: 0.99

# termination condition
dist_tol: 0.5 # body width
max_step: 500
max_collisions_allowed: 500
goal_format: polar

# sensor spec
#output: [sensor, rgb, depth, scan]
output: [task_obs, rgb, depth, scan, occupancy_grid]
# image
# Primesense Carmine 1.09 short-range RGBD sensor
# http://xtionprolive.com/primesense-carmine-1.09
fisheye: false
image_width: 160
image_height: 120
vertical_fov: 45
# depth
depth_low: 0.35
depth_high: 3.0
# scan
# SICK TIM571 scanning range finder
# https://docs.fetchrobotics.com/robot_hardware.html
# n_horizontal_rays is originally 661, sub-sampled 1/3
n_horizontal_rays: 220
n_vertical_beams: 1
laser_linear_range: 25.0
laser_angular_range: 220.0
min_laser_dist: 0.05
laser_link_name: base_laser_link

# sensor noise
depth_noise_rate: 0.0
scan_noise_rate: 0.0

# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: false

84 changes: 84 additions & 0 deletions gibson2/examples/configs/tiago_reaching.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
# scene
scene: igibson
scene_id: Rs_int
build_graph: true
load_texture: true
pybullet_load_texture: true
trav_map_type: no_obj
trav_map_resolution: 0.1
trav_map_erosion: 3
should_open_all_doors: true

# domain randomization
texture_randomization_freq: null
object_randomization_freq: null

# robot
robot: Tiago_Dual
wheel_velocity: 0.8
torso_lift_velocity: 0.8
arm_velocity: 0.8

# task
task: grasp_task
load_object_categories: [
bottom_cabinet,
bottom_cabinet_no_top,
top_cabinet,
dishwasher,
fridge,
microwave,
oven,
washer
dryer,
]


# reward
reward_type: l2
success_reward: 10.0
potential_reward_weight: 1.0
collision_reward_weight: -0.1

# discount factor
discount_factor: 0.99

# termination condition
dist_tol: 0.36 # body width
max_step: 500
max_collisions_allowed: 500

# misc config
initial_pos_z_offset: 0.1
collision_ignore_link_a_ids: [0, 1, 2] # ignore collisions with these robot links

# sensor spec
output: [task_obs, rgb, depth, seg, scan, occupancy_grid]
# image
# Primesense Carmine 1.09 short-range RGBD sensor
# http://xtionprolive.com/primesense-carmine-1.09
fisheye: false
image_width: 640
image_height: 480
vertical_fov: 45
# depth
depth_low: 0.35
depth_high: 3.0
# scan
# SICK TIM571 scanning range finder
# https://docs.fetchrobotics.com/robot_hardware.html
# n_horizontal_rays is originally 661, sub-sampled 1/3
n_horizontal_rays: 220
n_vertical_beams: 1
laser_linear_range: 25.0
laser_angular_range: 220.0
min_laser_dist: 0.05
laser_link_name: base_laser_link

# sensor noise
depth_noise_rate: 0.0
scan_noise_rate: 0.0

# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: false
73 changes: 73 additions & 0 deletions gibson2/examples/configs/tiago_single_point_nav.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
# scene
scene: stadium
model_id: Rs
is_interactive: false
build_graph: true
load_texture: true
trav_map_resolution: 0.1
trav_map_erosion: 3

# robot
robot: Tiago_Single
is_discrete: false
wheel_velocity: 1.0
torso_lift_velocity: 1.0
head_velocity: 0.8
arm_velocity: 0.9
gripper_velocity: 1.0

# task, observation and action
task: pointgoal # pointgoal|objectgoal|areagoal|reaching
target_dist_min: 1.0
target_dist_max: 10.0
initial_pos_z_offset: 0.1
additional_states_dim: 4

# reward
reward_type: geodesic
success_reward: 10.0
slack_reward: -0.01
potential_reward_weight: 1.0
collision_reward_weight: -0.1
collision_ignore_link_a_ids: [0, 1, 2] # ignore collisions with these robot links

# discount factor
discount_factor: 0.99

# termination condition
dist_tol: 0.5 # body width
max_step: 500
max_collisions_allowed: 500
goal_format: polar

# sensor spec
output: [sensor, rgb, depth, scan]
# image
# Primesense Carmine 1.09 short-range RGBD sensor
# http://xtionprolive.com/primesense-carmine-1.09
fisheye: false
image_width: 160
image_height: 120
vertical_fov: 45
# depth
depth_low: 0.35
depth_high: 3.0
# scan
# SICK TIM571 scanning range finder
# https://docs.fetchrobotics.com/robot_hardware.html
# n_horizontal_rays is originally 661, sub-sampled 1/3
n_horizontal_rays: 220
n_vertical_beams: 1
laser_linear_range: 25.0
laser_angular_range: 220.0
min_laser_dist: 0.05
laser_link_name: laser_link

# sensor noise
depth_noise_rate: 0.0
scan_noise_rate: 0.0

# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: false

Loading