diff --git a/cfg/active_grasp.yaml b/cfg/active_grasp.yaml index 77de7a2..18f82cc 100644 --- a/cfg/active_grasp.yaml +++ b/cfg/active_grasp.yaml @@ -15,6 +15,9 @@ grasp_controller: depth_topic: /camera/depth/image_rect_raw min_z_dist: 0.3 +cartesian_velocity_controller: + topic: /cartesian_velocity_controller/set_command + vgn: model: $(find vgn)/assets/models/vgn_conv.pth finger_depth: 0.05 diff --git a/launch/env.launch b/launch/env.launch index c241621..ac085c4 100644 --- a/launch/env.launch +++ b/launch/env.launch @@ -1,7 +1,7 @@ - + @@ -9,6 +9,7 @@ + diff --git a/scripts/bt_sim_node.py b/scripts/bt_sim_node.py index a56226e..f6947a8 100755 --- a/scripts/bt_sim_node.py +++ b/scripts/bt_sim_node.py @@ -156,7 +156,8 @@ class CartesianVelocityControllerPlugin(Plugin): super().__init__(rate) self.arm = arm self.model = model - rospy.Subscriber("command", Twist, self.target_cb) + topic = rospy.get_param("cartesian_velocity_controller/topic") + rospy.Subscriber(topic, Twist, self.target_cb) def target_cb(self, msg): self.dx_d = from_twist_msg(msg) diff --git a/src/active_grasp/controller.py b/src/active_grasp/controller.py index e7ff25d..cffa02c 100644 --- a/src/active_grasp/controller.py +++ b/src/active_grasp/controller.py @@ -48,7 +48,8 @@ class GraspController: def init_robot_connection(self): self.arm = PandaArmClient() self.gripper = PandaGripperClient() - self.cartesian_vel_pub = rospy.Publisher("command", Twist, queue_size=10) + topic = rospy.get_param("cartesian_velocity_controller/topic") + self.cartesian_vel_pub = rospy.Publisher(topic, Twist, queue_size=10) def init_moveit(self): self.moveit = MoveItClient("panda_arm")