nbv_sim/bt_sim_node.py

121 lines
3.9 KiB
Python
Raw Normal View History

2021-04-26 10:45:00 +02:00
#!/usr/bin/env python3
2021-04-15 10:44:08 +02:00
import argparse
2021-04-26 10:45:00 +02:00
import actionlib
2021-04-27 11:45:57 +02:00
import cv_bridge
2021-04-15 10:44:08 +02:00
import numpy as np
import rospy
2021-04-26 10:45:00 +02:00
import franka_gripper.msg
2021-04-15 10:44:08 +02:00
from geometry_msgs.msg import Pose
2021-04-28 11:24:51 +02:00
from sensor_msgs.msg import JointState, Image, CameraInfo
2021-04-26 20:10:52 +02:00
import std_srvs.srv
2021-04-15 10:44:08 +02:00
from robot_utils.controllers import CartesianPoseController
from robot_utils.ros.conversions import *
from robot_utils.ros.tf import TransformTree
2021-04-15 10:44:08 +02:00
2021-04-26 20:10:52 +02:00
from simulation import BtPandaEnv
2021-04-15 10:44:08 +02:00
CONTROLLER_UPDATE_RATE = 60
2021-04-27 11:45:57 +02:00
JOINT_PUBLISH_RATE = 60
CAM_PUBLISH_RATE = 5
2021-04-15 10:44:08 +02:00
class BtSimNode:
def __init__(self, gui):
self.sim = BtPandaEnv(gui=gui, sleep=False)
self.controller = CartesianPoseController(self.sim.arm)
2021-04-27 11:45:57 +02:00
self.cv_bridge = cv_bridge.CvBridge()
self.tf_tree = TransformTree()
2021-04-26 20:10:52 +02:00
self.reset_server = rospy.Service("reset", std_srvs.srv.Trigger, self.reset)
2021-04-26 10:45:00 +02:00
self.move_server = actionlib.SimpleActionServer(
"move",
franka_gripper.msg.MoveAction,
2021-04-27 11:45:57 +02:00
self.move,
False,
2021-04-26 20:10:52 +02:00
)
2021-04-27 11:45:57 +02:00
self.joint_pub = rospy.Publisher("joint_states", JointState, queue_size=10)
2021-04-28 11:24:51 +02:00
self.cam_info_pub = rospy.Publisher(
"/cam/depth/camera_info", CameraInfo, queue_size=10
)
self.cam_info_msg = to_camera_info_msg(self.sim.camera.info)
self.cam_info_msg.header.frame_id = "cam_optical_frame"
2021-04-27 11:45:57 +02:00
self.depth_pub = rospy.Publisher("/cam/depth/image_raw", Image, queue_size=10)
2021-04-26 20:10:52 +02:00
rospy.Subscriber("target", Pose, self.target_pose_cb)
self.step_cnt = 0
self.reset_requested = False
2021-04-26 10:45:00 +02:00
self.move_server.start()
T_base_task = Transform(Rotation.identity(), np.r_[0.2, -0.1, 0.1])
self.tf_tree.broadcast_static(T_base_task, "panda_link0", "task")
2021-04-26 20:10:52 +02:00
def reset(self, req):
self.reset_requested = True
rospy.sleep(1.0) # wait for the latest sim step to finish
self.sim.reset()
self.controller.set_target(self.sim.arm.pose())
self.step_cnt = 0
self.reset_requested = False
return std_srvs.srv.TriggerResponse(success=True)
2021-04-15 10:44:08 +02:00
def run(self):
rate = rospy.Rate(self.sim.rate)
while not rospy.is_shutdown():
2021-04-26 20:10:52 +02:00
if not self.reset_requested:
self.handle_updates()
self.sim.step()
self.step_cnt = (self.step_cnt + 1) % self.sim.rate
2021-04-15 10:44:08 +02:00
rate.sleep()
2021-04-26 10:45:00 +02:00
def handle_updates(self):
2021-04-15 10:44:08 +02:00
if self.step_cnt % int(self.sim.rate / CONTROLLER_UPDATE_RATE) == 0:
self.controller.update()
2021-04-27 11:45:57 +02:00
if self.step_cnt % int(self.sim.rate / JOINT_PUBLISH_RATE) == 0:
2021-04-26 10:45:00 +02:00
self.publish_joint_state()
2021-04-27 11:45:57 +02:00
if self.step_cnt % int(self.sim.rate / CAM_PUBLISH_RATE) == 0:
2021-04-28 11:24:51 +02:00
self.publish_cam_info()
2021-04-27 11:45:57 +02:00
self.publish_cam_imgs()
2021-04-15 10:44:08 +02:00
2021-04-26 10:45:00 +02:00
def publish_joint_state(self):
2021-04-15 10:44:08 +02:00
q, dq = self.sim.arm.get_state()
width = self.sim.gripper.read()
msg = JointState()
msg.header.stamp = rospy.Time.now()
msg.name = ["panda_joint{}".format(i) for i in range(1, 8)] + [
"panda_finger_joint1",
"panda_finger_joint2",
]
msg.position = np.r_[q, 0.5 * width, 0.5 * width]
msg.velocity = dq
2021-04-27 11:45:57 +02:00
self.joint_pub.publish(msg)
2021-04-28 11:24:51 +02:00
def publish_cam_info(self):
self.cam_info_msg.header.stamp = rospy.Time.now()
self.cam_info_pub.publish(self.cam_info_msg)
2021-04-27 11:45:57 +02:00
def publish_cam_imgs(self):
2021-04-28 11:24:51 +02:00
_, depth = self.sim.camera.update()
2021-04-27 11:45:57 +02:00
depth_msg = self.cv_bridge.cv2_to_imgmsg(depth)
self.depth_pub.publish(depth_msg)
2021-04-15 10:44:08 +02:00
2021-04-26 10:45:00 +02:00
def move(self, goal):
self.sim.gripper.move(goal.width)
self.move_server.set_succeeded()
def target_pose_cb(self, msg):
2021-04-15 10:44:08 +02:00
self.controller.set_target(from_pose_msg(msg))
def main(args):
rospy.init_node("bt_sim")
server = BtSimNode(args.gui)
server.run()
if __name__ == "__main__":
parser = argparse.ArgumentParser()
2021-04-26 10:45:00 +02:00
parser.add_argument("--gui", action="store_true")
args, _ = parser.parse_known_args()
2021-04-15 10:44:08 +02:00
main(args)