Read cartesian controller topic from rosparam

This commit is contained in:
Michel Breyer 2021-11-24 11:34:12 +01:00
parent 2e1f3eb4a7
commit bcd270414f
4 changed files with 9 additions and 3 deletions

View File

@ -15,6 +15,9 @@ grasp_controller:
depth_topic: /camera/depth/image_rect_raw depth_topic: /camera/depth/image_rect_raw
min_z_dist: 0.3 min_z_dist: 0.3
cartesian_velocity_controller:
topic: /cartesian_velocity_controller/set_command
vgn: vgn:
model: $(find vgn)/assets/models/vgn_conv.pth model: $(find vgn)/assets/models/vgn_conv.pth
finger_depth: 0.05 finger_depth: 0.05

View File

@ -1,7 +1,7 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<launch> <launch>
<arg name="launch_rviz" default="false" />
<arg name="simulation" default="true" /> <arg name="simulation" default="true" />
<arg name="launch_rviz" default="false" />
<!-- Load parameters --> <!-- Load parameters -->
<rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" /> <rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" />
@ -9,6 +9,7 @@
<!-- Load robot description --> <!-- Load robot description -->
<param name="robot_description" command="$(find xacro)/xacro $(find active_grasp)/assets/franka/panda_arm_hand.urdf.xacro" /> <param name="robot_description" command="$(find xacro)/xacro $(find active_grasp)/assets/franka/panda_arm_hand.urdf.xacro" />
<!-- Simulated environment -->
<group if="$(arg simulation)"> <group if="$(arg simulation)">
<node pkg="active_grasp" type="bt_sim_node.py" name="bt_sim" output="screen" /> <node pkg="active_grasp" type="bt_sim_node.py" name="bt_sim" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" /> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />

View File

@ -156,7 +156,8 @@ class CartesianVelocityControllerPlugin(Plugin):
super().__init__(rate) super().__init__(rate)
self.arm = arm self.arm = arm
self.model = model 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): def target_cb(self, msg):
self.dx_d = from_twist_msg(msg) self.dx_d = from_twist_msg(msg)

View File

@ -48,7 +48,8 @@ class GraspController:
def init_robot_connection(self): def init_robot_connection(self):
self.arm = PandaArmClient() self.arm = PandaArmClient()
self.gripper = PandaGripperClient() 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): def init_moveit(self):
self.moveit = MoveItClient("panda_arm") self.moveit = MoveItClient("panda_arm")