nbv_sim/scripts/hw_node.py

95 lines
3.0 KiB
Python
Raw Normal View History

2021-11-24 16:26:26 +01:00
#!/usr/bin/env python3
from controller_manager_msgs.srv import *
2021-12-08 12:39:00 +01:00
import geometry_msgs.msg
2021-12-03 13:52:07 +01:00
import numpy as np
2021-11-24 16:26:26 +01:00
import rospy
from active_grasp.bbox import AABBox, to_bbox_msg
2021-12-03 16:51:13 +01:00
from active_grasp.rviz import Visualizer
2021-11-24 16:26:26 +01:00
from active_grasp.srv import *
2021-12-03 13:52:07 +01:00
from robot_helpers.io import load_yaml
2021-12-08 12:39:00 +01:00
from robot_helpers.ros.conversions import to_pose_msg
2021-11-24 16:26:26 +01:00
from robot_helpers.ros.moveit import MoveItClient
2021-12-03 13:52:07 +01:00
from robot_helpers.ros.panda import PandaGripperClient
from robot_helpers.spatial import Transform
2021-11-24 16:26:26 +01:00
class HwNode:
def __init__(self):
2021-12-03 13:52:07 +01:00
self.load_parameters()
self.init_robot_connection()
2021-12-03 16:51:13 +01:00
self.init_visualizer()
2021-11-24 16:26:26 +01:00
self.advertise_services()
2021-12-03 13:52:07 +01:00
rospy.spin()
def load_parameters(self):
2021-12-03 16:51:13 +01:00
self.cfg = rospy.get_param("hw")
self.T_base_roi = Transform.from_matrix(np.loadtxt(self.cfg["roi_calib_file"]))
2021-12-03 13:52:07 +01:00
def init_robot_connection(self):
2021-12-03 14:10:32 +01:00
self.gripper = PandaGripperClient()
2021-12-06 09:29:39 +01:00
self.switch_controller = rospy.ServiceProxy(
2021-11-24 16:26:26 +01:00
"controller_manager/switch_controller", SwitchController
)
self.moveit = MoveItClient("panda_arm")
2021-12-08 12:39:00 +01:00
rospy.Timer(rospy.Duration(1), self.publish_table_co)
2021-11-24 16:26:26 +01:00
2021-12-03 16:51:13 +01:00
def init_visualizer(self):
self.vis = Visualizer()
rospy.Timer(rospy.Duration(1), self.draw_bbox)
2021-11-24 16:26:26 +01:00
def advertise_services(self):
rospy.Service("seed", Seed, self.seed)
rospy.Service("reset", Reset, self.reset)
def seed(self, req):
2021-12-06 18:08:50 +01:00
self.rng = np.random.default_rng(req.seed)
rospy.loginfo(f"Seeded the rng with {req.seed}.")
2021-11-24 16:26:26 +01:00
return SeedResponse()
def reset(self, req):
2021-12-03 16:51:13 +01:00
q0, bbox = self.load_config()
2021-12-03 13:52:07 +01:00
# Move to the initial configuration
self.switch_to_joint_trajectory_controller()
2021-12-06 18:08:50 +01:00
q0 += self.rng.uniform(-0.069, 0.069, 7)
2021-12-06 14:18:51 +01:00
self.moveit.goto(q0, velocity_scaling=0.4)
2021-12-06 09:29:39 +01:00
self.gripper.move(0.08)
2021-12-03 13:52:07 +01:00
return ResetResponse(to_bbox_msg(bbox))
2021-12-03 16:51:13 +01:00
def load_config(self):
scene_config = load_yaml(self.cfg["scene_file"])
q0 = scene_config["q0"]
bbox_min = self.T_base_roi.apply(scene_config["target"]["min"])
bbox_max = self.T_base_roi.apply(scene_config["target"]["max"])
bbox = AABBox(bbox_min, bbox_max)
return q0, bbox
2021-12-03 13:52:07 +01:00
def switch_to_joint_trajectory_controller(self):
2021-11-24 16:26:26 +01:00
req = SwitchControllerRequest()
req.start_controllers = ["position_joint_trajectory_controller"]
req.stop_controllers = ["cartesian_velocity_controller"]
2021-12-03 13:52:07 +01:00
req.strictness = 1
2021-11-24 16:26:26 +01:00
self.switch_controller(req)
2021-12-03 16:51:13 +01:00
def draw_bbox(self, event):
_, bbox = self.load_config()
self.vis.bbox("panda_link0", bbox)
2021-12-08 12:39:00 +01:00
def publish_table_co(self, event):
msg = geometry_msgs.msg.PoseStamped()
msg.header.frame_id = "panda_link0"
2022-01-11 11:19:21 +01:00
msg.pose = to_pose_msg(self.T_base_roi * Transform.t_[0.15, 0.15, 0.005])
2021-12-08 12:39:00 +01:00
self.moveit.scene.add_box("table", msg, size=(0.8, 0.8, 0.01))
2021-11-24 16:26:26 +01:00
def main():
rospy.init_node("hw")
HwNode()
if __name__ == "__main__":
main()