nbv_sim/run.py

84 lines
2.0 KiB
Python
Raw Normal View History

2021-04-15 10:44:08 +02:00
import argparse
import rospy
2021-04-26 20:10:52 +02:00
from geometry_msgs.msg import Pose
import std_srvs.srv
2021-04-15 10:44:08 +02:00
2021-04-26 20:10:52 +02:00
from policies import get_policy
2021-05-26 14:46:12 +02:00
from robot_tools.ros.conversions import *
from robot_tools.ros.panda import PandaGripperClient
2021-04-26 10:45:00 +02:00
class GraspController:
def __init__(self, policy, rate):
self.policy = policy
self.rate = rate
2021-05-26 14:46:12 +02:00
self.reset_client = rospy.ServiceProxy("/reset", std_srvs.srv.Trigger)
self.target_pose_pub = rospy.Publisher("/cmd", Pose, queue_size=10)
self.gripper = PandaGripperClient()
2021-04-26 20:10:52 +02:00
rospy.sleep(1.0)
def run(self):
self.reset()
self.explore()
self.execute_grasp()
def reset(self):
req = std_srvs.srv.TriggerRequest()
self.reset_client(req)
2021-05-26 14:46:12 +02:00
rospy.sleep(1.0) # wait for states to be updated
2021-04-26 10:45:00 +02:00
def explore(self):
r = rospy.Rate(self.rate)
self.policy.start()
2021-04-26 20:10:52 +02:00
while not self.policy.done:
self.policy.update()
2021-04-26 10:45:00 +02:00
r.sleep()
def execute_grasp(self):
self.gripper.move(0.08)
rospy.sleep(1.0)
target = self.policy.best_grasp
2021-05-26 14:46:12 +02:00
if not target:
return
2021-04-26 10:45:00 +02:00
self.target_pose_pub.publish(to_pose_msg(target))
rospy.sleep(2.0)
self.gripper.move(0.0)
rospy.sleep(1.0)
target.translation[2] += 0.1
self.target_pose_pub.publish(to_pose_msg(target))
rospy.sleep(2.0)
2021-04-29 10:50:33 +02:00
self.gripper.move(0.08)
rospy.sleep(1.0)
2021-04-26 10:45:00 +02:00
2021-04-15 10:44:08 +02:00
2021-05-26 14:46:12 +02:00
def create_parser():
parser = argparse.ArgumentParser()
parser.add_argument(
"--policy",
type=str,
choices=[
"single-view",
"fixed-trajectory",
],
)
parser.add_argument("--rate", type=int, default=10)
return parser
def main():
2021-04-29 10:50:33 +02:00
rospy.init_node("active_grasp")
2021-05-26 14:46:12 +02:00
parser = create_parser()
args = parser.parse_args()
2021-04-15 10:44:08 +02:00
policy = get_policy(args.policy)
2021-04-26 10:45:00 +02:00
gc = GraspController(policy, args.rate)
2021-04-26 20:10:52 +02:00
gc.run()
2021-04-15 10:44:08 +02:00
if __name__ == "__main__":
2021-05-26 14:46:12 +02:00
main()