Skip to content

Commit

Permalink
Improvements in Goal node
Browse files Browse the repository at this point in the history
  • Loading branch information
sergio-maal committed Apr 4, 2024
1 parent 923f63e commit 82d266a
Showing 1 changed file with 10 additions and 8 deletions.
18 changes: 10 additions & 8 deletions cognitive_nodes/cognitive_nodes/goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class Goal(CognitiveNode):
"""
Goal class
"""
def __init__(self, name='goal', data = None, class_name = 'cognitive_nodes.goal.Goal', space_class = None, space = None, **params):
def __init__(self, name='goal', data = None, class_name = 'cognitive_nodes.goal.Goal', space_class = None, space = None, robot_service = 'simulator/', **params):
"""
Constructor of the Goal class
Expand All @@ -31,6 +31,8 @@ def __init__(self, name='goal', data = None, class_name = 'cognitive_nodes.goal.
:type space_class: str
:param space: The space used to define the Goal
:type space: cognitive_nodes.space
:param robot_service: The ROS service prefix to connect with robot or simulator
:type robot_service: str
"""
super().__init__(name, class_name, **params)
self.register_in_LTM({})
Expand All @@ -39,7 +41,7 @@ def __init__(self, name='goal', data = None, class_name = 'cognitive_nodes.goal.
self.start = None
self.end = None
self.period = None
self.sim_service = 'mdb_simulator'
self.robot_service = robot_service
self.old_perception = []

if data:
Expand Down Expand Up @@ -256,7 +258,7 @@ def calculate_closest_position(self, angle):
closest_position_client.destroy_node()
return dist_near, ang_near

def object_pickable_with_two_hands(self):
def object_pickable_with_two_hands_request(self):
"""
Check of an obkect is pickable with the two hands of the robot
Expand Down Expand Up @@ -410,7 +412,7 @@ def ball_and_box_on_the_same_side(self):
break
return same_side

def object_pickable_withtwohands(self):
def object_pickable_with_two_hands(self):
"""
Check if an object can be hold with two hands.
Expand All @@ -421,7 +423,7 @@ def object_pickable_withtwohands(self):
"""
pickable = False
for cylinder in self.perception["cylinders"]:
pickable = (not Goal.object_held()) and self.object_pickable_withtwohands(
pickable = (not Goal.object_held()) and self.object_pickable_with_two_hands_request(
cylinder["distance"], cylinder["angle"]
)
if pickable:
Expand Down Expand Up @@ -624,7 +626,7 @@ def get_reward(self):
for _, activation in zip(self.perception, self.activation):
if activation > self.threshold:
if (
self.object_pickable_withtwohands()
self.object_pickable_with_two_hands()
and (not self.object_in_close_box())
and (not self.object_with_robot())
):
Expand Down Expand Up @@ -760,7 +762,7 @@ def get_reward(self):
elif not self.object_held_before():
self.reward = 0.3
elif not self.object_held_before():
if self.object_pickable_withtwohands():
if self.object_pickable_with_two_hands():
self.reward = 0.3
elif self.object_was_approximated():
self.reward = 0.2
Expand All @@ -785,7 +787,7 @@ def get_reward(self):
if not self.object_held_before():
self.reward = 0.6
elif not self.object_held_before():
if self.object_pickable_withtwohands():
if self.object_pickable_with_two_hands():
self.reward = 0.3
elif self.object_was_approximated():
self.reward = 0.2
Expand Down

0 comments on commit 82d266a

Please sign in to comment.