Skip to content

Commit

Permalink
release 0.1
Browse files Browse the repository at this point in the history
  • Loading branch information
Near32 committed Oct 6, 2017
1 parent 2794118 commit 94ab571
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 4 deletions.
2 changes: 1 addition & 1 deletion launch/empty_world.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<arg name="world_file" default="$(find GazeboDomainRandom)/models/GazeboDomainRandom/worlds/empty+light.world"/>
<arg name="gui" default="true"/>
<arg name="gui" default="false"/>


<include file="$(find gazebo_ros)/launch/empty_world.launch">
Expand Down
10 changes: 10 additions & 0 deletions src/GazeboDomainRandom/GazeboDomainRandom.py
Original file line number Diff line number Diff line change
Expand Up @@ -384,4 +384,14 @@ def project(self, x) :
projx[i] /= projx[2]+1e-6

return projx

def setPause(self,pause=True) :
if pause==True :
subprocess.Popen(['rosservice call /gazebo/pause_physics'], shell=True, env=self.env)
rospy.loginfo("ENVIRONMENT "+str(self.port)+" PHYSICS : PAUSED.\n")
else :
subprocess.Popen(['rosservice call /gazebo/unpause_physics'], shell=True, env=self.env)
rospy.loginfo("ENVIRONMENT "+str(self.port)+" PHYSICS : UNPAUSED.\n")



9 changes: 6 additions & 3 deletions src/createDataset-auto.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ def create_dataset(path='./dataset/') :
#XML generator :
genXML = XMLGenerator(path_out=path)
#index to name the pictures :
date = '2017_09_22__'
date = '2017_10_06__'
indexIMG = 0
#create the images folder :
pathimg = 'images/'
Expand Down Expand Up @@ -74,6 +74,7 @@ def create_dataset(path='./dataset/') :
fovy = 120
altitude = 0.45
camera = Camera(fovy=fovy,altitude=altitude,port=cfact.port, env=cfact.env)
camera.setPause(False)
camera.spawn()

#retrieve the position of the model :
Expand Down Expand Up @@ -152,9 +153,10 @@ def create_dataset(path='./dataset/') :
pose3d = [ np.reshape( model.getPose()[0,0:3], (3,1) ) for model in model_params ]
#REFRAMING :
pose3d = reframing(pose3d)
time.sleep(3)

elif key == ord('c') :
#create new config :
#change Orientations :
cfact.changeOrientation()
cfact.changeSpawned()

Expand All @@ -166,7 +168,7 @@ def create_dataset(path='./dataset/') :
pose3d = reframing(pose3d)

elif key == ord('v') :
#create new config :
#change Positions :
cfact.changePose()
cfact.changeSpawned()

Expand All @@ -178,6 +180,7 @@ def create_dataset(path='./dataset/') :
pose3d = reframing(pose3d)

elif key == ord('p') :
#Register the image into the dataset with its annotations :
listobj = []
for i in range(len(pose3d)) :
xp = pose3d[i].copy()
Expand Down

0 comments on commit 94ab571

Please sign in to comment.