-
Notifications
You must be signed in to change notification settings - Fork 16
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
Receptionist update with deepface #212
Changes from all commits
00bcbe0
1c6becd
0c3b2a8
4d34852
6a38d09
fd37557
f7e06ba
752c5a5
810a020
5de4a38
0c4629f
547a9ed
f627362
1318992
33f6a12
278f076
16ff9e1
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,19 +1,49 @@ | ||
import smach_ros | ||
import smach | ||
import actionlib | ||
import rospy | ||
from control_msgs.msg import PointHeadGoal, PointHeadAction | ||
from geometry_msgs.msg import Point, PointStamped | ||
from std_msgs.msg import Header | ||
from actionlib_msgs.msg import GoalStatus | ||
|
||
|
||
class LookToPoint(smach_ros.SimpleActionState): | ||
class LookToPoint(smach.State): | ||
def __init__(self): | ||
super(LookToPoint, self).__init__( | ||
"/head_controller/point_head_action", | ||
PointHeadAction, | ||
goal_cb=lambda ud, _: PointHeadGoal( | ||
pointing_frame="head_2_link", | ||
pointing_axis=Point(1.0, 0.0, 0.0), | ||
max_velocity=1.0, | ||
target=ud.pointstamped, | ||
smach.State.__init__( | ||
self, | ||
outcomes=["succeeded", "aborted", "timed_out"], | ||
input_keys=["point"], | ||
) | ||
self.client = actionlib.SimpleActionClient( | ||
"/head_controller/point_head_action", PointHeadAction | ||
) | ||
self.client.wait_for_server() | ||
|
||
def execute(self, userdata): | ||
# Define the goal | ||
goal = PointHeadGoal( | ||
pointing_frame="head_2_link", | ||
pointing_axis=Point(1.0, 0.0, 0.0), | ||
max_velocity=1.0, | ||
target=PointStamped( | ||
header=Header(frame_id="map"), | ||
point=userdata.point, | ||
), | ||
input_keys=["pointstamped"], | ||
) | ||
|
||
# Send the goal | ||
self.client.send_goal(goal) | ||
|
||
# Wait for the result with a timeout of 7 seconds | ||
finished_within_time = self.client.wait_for_result(rospy.Duration(7.0)) | ||
|
||
if finished_within_time: | ||
state = self.client.get_state() | ||
if state == GoalStatus.SUCCEEDED: | ||
return "succeeded" | ||
else: | ||
return "aborted" | ||
else: | ||
self.client.cancel_goal() | ||
return "timed_out" |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1 +1,8 @@ | ||
If you would like to view the documentation in the browser, ensure you have at [Node.js v16.x](https://nodejs.org/en) installed. | ||
|
||
|
||
Please make sure the following models are installed in order to run this code: | ||
|
||
- lasr_vision_yolov8 requires yolov8n-seg.pt in lasr_vision_yolov8/models/ | ||
- lasr_vision_feature_extraction requires model.pth in lasr_vision_feature_extraction/models/ | ||
- lasr_vision_clip requires a model from hugging face, this can be downloaded by running 'rosrun lasr_vision_clip vqa' |
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
@@ -1,28 +1,32 @@ | ||||||
#!/usr/bin/env python3 | ||||||
import rospy | ||||||
from receptionist.state_machine import Receptionist | ||||||
import smach | ||||||
import smach_ros | ||||||
|
||||||
from geometry_msgs.msg import Pose, Point, Quaternion | ||||||
from shapely.geometry import Polygon | ||||||
|
||||||
if __name__ == "__main__": | ||||||
rospy.init_node("receptionist_robocup") | ||||||
wait_pose_param = rospy.get_param("/receptionist/wait_pose") | ||||||
# wait_pose_param = rospy.get_param("/receptionist/wait_pose") | ||||||
wait_pose_param = rospy.get_param("/wait_pose/") | ||||||
|
||||||
wait_pose = Pose( | ||||||
position=Point(**wait_pose_param["position"]), | ||||||
orientation=Quaternion(**wait_pose_param["orientation"]), | ||||||
) | ||||||
|
||||||
wait_area_param = rospy.get_param("/receptionist/wait_area") | ||||||
wait_area_param = rospy.get_param("/wait_area") | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. /receptionist/... breaks the code. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. done |
||||||
wait_area = Polygon(wait_area_param) | ||||||
|
||||||
seat_pose_param = rospy.get_param("/receptionist/seat_pose") | ||||||
seat_pose_param = rospy.get_param("/seat_pose") | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. /receptionist/... breaks the code. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. done |
||||||
seat_pose = Pose( | ||||||
position=Point(**seat_pose_param["position"]), | ||||||
orientation=Quaternion(**seat_pose_param["orientation"]), | ||||||
) | ||||||
|
||||||
seat_area_param = rospy.get_param("/receptionist/seat_area") | ||||||
seat_area_param = rospy.get_param("/seat_area") | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. /receptionist/... breaks the code. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. done |
||||||
seat_area = Polygon(seat_area_param) | ||||||
|
||||||
receptionist = Receptionist( | ||||||
|
@@ -35,6 +39,11 @@ | |||||
"drink": "beer", | ||||||
}, | ||||||
) | ||||||
|
||||||
sis = smach_ros.IntrospectionServer("smach_server", receptionist, "/SM_ROOT") | ||||||
sis.start() | ||||||
outcome = receptionist.execute() | ||||||
|
||||||
sis.stop() | ||||||
rospy.loginfo(f"Receptionist finished with outcome: {outcome}") | ||||||
rospy.spin() |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
/receptionist/... breaks the code.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
If you apply the update to the launch file, that sets "ns" to "receptionist", I think this should work
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done