Skip to content

Commit

Permalink
[Receptionist] implemented feedback
Browse files Browse the repository at this point in the history
  • Loading branch information
Julislz committed Dec 13, 2024
1 parent 801bbec commit a3ae645
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 141 deletions.
10 changes: 4 additions & 6 deletions demos/pycram_receptionist_demo/receptionist_clean_code.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,13 @@
from pycram.designators.motion_designator import *
from pycram.designators.object_designator import *
from pycram.process_module import real_robot
from pycram.ros_utils.robot_state_updater import RobotStateUpdater
from pycram.ros_utils.object_state_updater import RobotStateUpdater
from pycram.ros_utils.viz_marker_publisher import VizMarkerPublisher
from pycram.utilities.robocup_utils import ImageSwitchPublisher
from pycram.world_concepts.world_object import Object
from pycram.worlds.bullet_world import BulletWorld
import rospy
from pycrap import Robot

# Initialize the Bullet world for simulation
world = BulletWorld()
Expand All @@ -20,17 +21,14 @@
v = VizMarkerPublisher()

# Create and configure the robot object
robot = Object("hsrb", ObjectType.ROBOT, "../../resources/hsrb.urdf", pose=Pose([0, 0, 0]))
robot = Object("hsrb", Robot, "../../resources/hsrb.urdf", pose=Pose([0, 0, 0]))
RobotStateUpdater("/tf", "/giskard_joint_states")
image_switch_publisher = ImageSwitchPublisher()

# Create environmental objects
apartment = Object("kitchen", ObjectType.ENVIRONMENT, "suturo_lab_2.urdf")

# variables for communication with nlp
response = [None, None, None]
callback = False
pub_nlp = rospy.Publisher('/startListener', String, queue_size=16)
# class object for communication with nlp
nlp = NLP_Functions()

# Declare variables for humans
Expand Down
120 changes: 0 additions & 120 deletions src/pycram/ros_utils/robot_state_updater.py

This file was deleted.

15 changes: 0 additions & 15 deletions src/pycram/utilities/robocup_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -212,21 +212,6 @@ def pub_now(self, image_id):
rospy.loginfo("Image switch request published")


class HSRBMoveGripperReal():
def __init__(self, latch=True):
self.pub = rospy.Publisher('/hsrb/gripper_controller/grasp/goal', GripperApplyEffortActionGoal,
queue_size=10, latch=latch)
self.msg = GripperApplyEffortActionGoal()

def pub_now(self, motion: str):
if motion == "open":
self.msg.goal.effort = 0.8
self.pub.publish(self.msg)
elif motion == "close":
self.msg.goal.effort = -0.8
self.pub.publish(self.msg)


class GraspListener:
def __init__(self):

Expand Down

0 comments on commit a3ae645

Please sign in to comment.