Skip to content

Commit

Permalink
Merge branch 'main' into insert/feat/bodypix
Browse files Browse the repository at this point in the history
  • Loading branch information
jws-1 authored Jan 8, 2024
2 parents 5218807 + 8551b29 commit f2d4ecf
Show file tree
Hide file tree
Showing 6 changed files with 325 additions and 0 deletions.
5 changes: 5 additions & 0 deletions skills/config/demo.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
living_room:
table:
location:
position: {x: 1.526343, y: 0.523707, z: 0.0024719}
orientation: { x: 0.0, y: 0.0, z: 0.746444684543, w: 0.665447468188 }
6 changes: 6 additions & 0 deletions skills/launch/demo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<arg name="config" default="demo"/>
<rosparam command="load" file="$(find lasr_skills)/config/$(arg config).yaml" />
<node pkg="lasr_skills" type="go_to_location.py" name="go_to_location" output="screen" />
<!-- <node pkg="lasr_skills" type="go_to_semantic_location.py" name="go_to_semantic_location" output="screen" />-->
</launch>
3 changes: 3 additions & 0 deletions skills/src/lasr_skills/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,6 @@
from .wait_for_person_in_area import WaitForPersonInArea
from .describe_people import DescribePeople
from .look_to_point import LookToPoint
from .look_to_point import LookToPoint
from .go_to_location import GoToLocation
from .go_to_semantic_location import GoToSemanticLocation
31 changes: 31 additions & 0 deletions skills/src/lasr_skills/go_to_location.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python3

import rospy
import smach
from tiago_controllers.controllers import Controllers
from geometry_msgs.msg import Point, Quaternion, Pose

class GoToLocation(smach.State):

def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'failed'], input_keys=['location'])
self.controllers = Controllers()

def execute(self, userdata):
try:
status = self.controllers.base_controller.sync_to_pose(userdata.location)
if status:
return 'succeeded'
return 'failed'
except rospy.ERROR as e:
rospy.logwarn(f"Unable to go to location. {userdata.location} -> ({str(e)})")
return 'failed'

if __name__ == '__main__':
rospy.init_node('go_to_location')
sm = smach.StateMachine(outcomes=['succeeded', 'failed'])
loc = rospy.get_param('/living_room/table/location')
sm.userdata.location = Pose(position=Point(**loc['position']), orientation=Quaternion(**loc['orientation']))
with sm:
smach.StateMachine.add('GoToLocation', GoToLocation(), transitions={'succeeded': 'succeeded', 'failed': 'failed'})
sm.execute()
30 changes: 30 additions & 0 deletions skills/src/lasr_skills/go_to_semantic_location.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#!/usr/bin/env python3

import rospy
import smach
from tiago_controllers.controllers import Controllers
from geometry_msgs.msg import Point, Quaternion, Pose

class GoToSemanticLocation(smach.State):

def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'failed'], input_keys=['location'])
self.controllers = Controllers()

def execute(self, userdata):
loc = rospy.get_param(f"{userdata.location}/location")
try:
status = self.controllers.base_controller.sync_to_pose(Pose(position=Point(**loc['position']), orientation=Quaternion(**loc['orientation'])))
if status:
return 'succeeded'
return 'failed'
except rospy.ERROR as e:
rospy.logwarn(f"Unable to go to location. {loc} -> ({str(e)})")
return 'failed'
if __name__ == '__main__':
rospy.init_node('go_to_semantic_location')
sm = smach.StateMachine(outcomes=['succeeded', 'failed'])
sm.userdata.location = '/living_room/table'
with sm:
smach.StateMachine.add('GoToSemanticLocation', GoToSemanticLocation(), transitions={'succeeded': 'succeeded', 'failed': 'failed'})
sm.execute()
Loading

0 comments on commit f2d4ecf

Please sign in to comment.