some fixes

This commit is contained in:
fxia22 2019-05-07 22:09:21 -07:00
parent d9a709c1d5
commit 1aab7b3e96
14 changed files with 62 additions and 18 deletions

View File

@ -10,6 +10,7 @@ arm_velocity: 0.01
# task, observation and action
task: reaching # pointgoal|objectgoal|areagoal|reaching
fisheye: false
initial_pos: [-1.0, -1.0, 0.0]
initial_orn: [0.0, 0.0, 0.0]

View File

@ -10,6 +10,7 @@ arm_velocity: 0.01
# task, observation and action
task: pointgoal # pointgoal|objectgoal|areagoal|reaching
fisheye: false
initial_pos: [0, -5, 0.0]
initial_orn: [0.0, 0.0, 0.0]

View File

@ -9,6 +9,7 @@ velocity: 0.1
# task, observation and action
task: pointgoal # pointgoal|objectgoal|areagoal|reaching
fisheye: false
initial_pos: [-1.0, -1.0, 0.0]
initial_orn: [0.0, 0.0, 0.0]

View File

@ -9,6 +9,7 @@ velocity: 0.1
# task, observation and action
task: pointgoal # pointgoal|objectgoal|areagoal|reaching
fisheye: false
initial_pos: [-1.0, -1.0, 0.0]
initial_orn: [0.0, 0.0, 0.0]

View File

@ -8,6 +8,7 @@ velocity: 0.1
# task, observation and action
task: pointgoal # pointgoal|objectgoal|areagoal|reaching
fisheye: false
initial_pos: [-1.0, -1.0, 0.0]
initial_orn: [0.0, 0.0, 0.0]

View File

@ -12,7 +12,7 @@
<node name="turtlebot_gibson_sim" pkg="gibson2-ros" type="turtlebot_rgbd.py" output="screen">
</node>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="5.0" />
</node>

View File

@ -5,7 +5,8 @@ import rospy
from std_msgs.msg import Float32, Int64, Header
from geometry_msgs.msg import Twist
from sensor_msgs import point_cloud2 as pc2
from sensor_msgs.msg import Image, CameraInfo, PointCloud2
from sensor_msgs.msg import CameraInfo, PointCloud2
from sensor_msgs.msg import Image as ImageMsg
from nav_msgs.msg import Odometry
import rospkg
import numpy as np
@ -24,11 +25,11 @@ class SimNode:
self.cmdx = 0.0
self.cmdy = 0.0
self.image_pub = rospy.Publisher("/gibson_ros/camera/rgb/image",Image, queue_size=10)
self.depth_pub = rospy.Publisher("/gibson_ros/camera/depth/image",Image, queue_size=10)
self.image_pub = rospy.Publisher("/gibson_ros/camera/rgb/image",ImageMsg, queue_size=10)
self.depth_pub = rospy.Publisher("/gibson_ros/camera/depth/image",ImageMsg, queue_size=10)
self.lidar_pub = rospy.Publisher("/gibson_ros/lidar/points", PointCloud2, queue_size=10)
self.depth_raw_pub = rospy.Publisher("/gibson_ros/camera/depth/image_raw",Image, queue_size=10)
self.depth_raw_pub = rospy.Publisher("/gibson_ros/camera/depth/image_raw",ImageMsg, queue_size=10)
self.odom_pub = rospy.Publisher("/odom",Odometry, queue_size=10)
self.gt_odom_pub = rospy.Publisher("/ground_truth_odom", Odometry, queue_size=10)
@ -92,6 +93,7 @@ class SimNode:
self.lidar_pub.publish(lidar_message)
# odometry
self.env.robots[0].calc_state()
odom = [np.array(self.env.robots[0].body_xyz) - np.array(self.env.config["initial_pos"]),
np.array(self.env.robots[0].body_rpy)]
@ -134,8 +136,6 @@ class SimNode:
gt_odom_msg.twist.twist.angular.z = (self.cmdy - self.cmdx) * 5 * 8.695652173913043
self.gt_odom_pub.publish(gt_odom_msg)
rospy.spin()
def cmd_callback(self,data):
self.cmdx = data.linear.x/10.0 - data.angular.z / (10*8.695652173913043)
self.cmdy = data.linear.x/10.0 + data.angular.z / (10*8.695652173913043)

View File

@ -20,7 +20,7 @@ dist_tol: 0.5
terminal_reward: 5000
discount_factor: 1.0
additional_states_dim: 5
additional_states_dim: 3
fisheye: true
fov: 1.57
@ -52,3 +52,7 @@ speed:
mode: web_ui #gui|headless
verbose: false
fast_lq_render: true
# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: true

View File

@ -18,7 +18,7 @@ class Simulator:
p.setGravity(0, 0, -self.gravity)
# renderer
self.renderer = MeshRenderer(width=resolution, height=resolution, device_idx=device_idx)
self.renderer = MeshRenderer(width=resolution, height=resolution, device_idx=device_idx, use_fisheye=use_fisheye)
self.resolution = resolution
self.device_idx = device_idx
self.renderer.set_fov(90)
@ -80,7 +80,7 @@ class Simulator:
new_object = object.load()
self.objects.append(new_object)
for shape in p.getVisualShapeData(new_object):
id, _, type, _, filename = shape[:5]
id, link_id, type, dimensions, filename, rel_pos, rel_orn, color = shape[:8]
if type == p.GEOM_MESH:
filename = filename.decode('utf-8')
print(filename, self.visual_objects)

View File

@ -9,9 +9,9 @@ class BaseEnv(gym.Env):
'''
a basic environment, step, observation and reward not implemented
'''
def __init__(self, config_file, mode='headless'):
def __init__(self, config_file, mode='headless', device_idx=0):
self.config = parse_config(config_file)
self.simulator = Simulator(mode=mode, use_fisheye=self.config['fisheye'])
self.simulator = Simulator(mode=mode, use_fisheye=self.config.get('fisheye', False), device_idx=device_idx)
if self.config['scene'] == 'stadium':
scene = StadiumScene()
elif self.config['scene'] == 'building':
@ -28,7 +28,10 @@ class BaseEnv(gym.Env):
robot = Humanoid(self.config)
elif self.config['robot'] == 'JR2':
robot = JR2(self.config)
elif self.config['robot'] == 'JR2_Kinova':
robot = JR2_Kinova(self.config)
else:
print('robot not defined')
self.scene = scene
self.robots = [robot]
for robot in self.robots:

View File

@ -45,6 +45,7 @@ class NavigateEnv(BaseEnv):
self.physics_timestep = physics_timestep
self.simulator.set_timestep(physics_timestep)
self.simulator_loop = int(self.action_timestep / self.simulator.timestep)
self.output = self.config['output']
self.sensor_dim = self.robots[0].sensor_dim + self.additional_states_dim
self.action_dim = self.robots[0].action_dim
@ -80,8 +81,20 @@ class NavigateEnv(BaseEnv):
# variable initialization
self.potential = 1.0
self.current_step = 0
self.max_step = 200
self.output = self.config['output']
self.current_episode = 0
self.max_step = self.config.get('max_step', float('inf'))
self.visual_object_at_initial_target_pos = self.config.get('visual_object_at_initial_target_pos', False)
if self.visual_object_at_initial_target_pos:
self.initial_pos_vis_obj = VisualObject(rgba_color=[1, 0, 0, 0.5])
self.target_pos_vis_obj = VisualObject(rgba_color=[0, 0, 1, 0.5])
self.initial_pos_vis_obj.load()
if self.config.get('target_visual_object_visible_to_agent', False):
self.simulator.import_object(self.target_pos_vis_obj)
else:
self.target_pos_vis_obj.load()
def reload(self, config_file):
super().reload(config_file)
@ -135,6 +148,17 @@ class NavigateEnv(BaseEnv):
self.observation_space = gym.spaces.Dict(observation_space)
self.action_space = self.robots[0].action_space
self.visual_object_at_initial_target_pos = self.config.get('visual_object_at_initial_target_pos', False)
if self.visual_object_at_initial_target_pos:
self.initial_pos_vis_obj = VisualObject(rgba_color=[1, 0, 0, 0.5])
self.target_pos_vis_obj = VisualObject(rgba_color=[0, 0, 1, 0.5])
self.initial_pos_vis_obj.load()
if self.config.get('target_visual_object_visible_to_agent', False):
self.simulator.import_object(self.target_pos_vis_obj)
else:
self.target_pos_vis_obj.load()
def get_additional_states(self):
relative_position = self.target_pos - self.robots[0].get_position()
# rotate relative position back to body point of view

View File

@ -80,7 +80,7 @@ setup(name='gibson2',
install_requires=[
'numpy>=1.10.4',
'pyglet>=1.2.0',
'gym==0.9.4',
'gym==0.12',
'Pillow>=3.3.0',
'PyYAML>=3.12',
'numpy>=1.13',

View File

@ -13,6 +13,7 @@ initial_pos: [-2.5, -1.0, 0.0]
target_orn: [0.0, 0.0, 0.0]
target_pos: [-5.0, 3.2, 0.0]
fisheye: false
is_discrete: false
additional_states_dim: 3
@ -39,6 +40,10 @@ random:
output: [sensor, rgb, depth, rgb_filled]
# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: true
resolution: 256
fov: 1.57

View File

@ -22,10 +22,9 @@ dist_tol: 0.5
terminal_reward: 5000
discount_factor: 1.0
additional_states_dim: 5
fov: 1.57
is_discrete: false
fisheye: false
debug: true
# display
@ -53,3 +52,7 @@ speed:
mode: web_ui #gui|headless
verbose: false
fast_lq_render: true
# visual objects
visual_object_at_initial_target_pos: true
target_visual_object_visible_to_agent: true