Read gripper force from the config file
This commit is contained in:
parent
00fb19f5eb
commit
e5da49d0a6
@ -1,6 +1,7 @@
|
|||||||
bt_sim:
|
bt_sim:
|
||||||
gui: False
|
gui: False
|
||||||
cam_noise: False
|
cam_noise: False
|
||||||
|
gripper_force: 10
|
||||||
scene: mustard1.yaml
|
scene: mustard1.yaml
|
||||||
|
|
||||||
grasp_controller:
|
grasp_controller:
|
||||||
|
@ -242,6 +242,7 @@ class GraspActionPlugin(Plugin):
|
|||||||
super().__init__(rate)
|
super().__init__(rate)
|
||||||
self.gripper = gripper
|
self.gripper = gripper
|
||||||
self.dt = 1.0 / self.rate
|
self.dt = 1.0 / self.rate
|
||||||
|
self.force = rospy.get_param("~gripper_force")
|
||||||
self.init_action_server()
|
self.init_action_server()
|
||||||
|
|
||||||
def init_action_server(self):
|
def init_action_server(self):
|
||||||
@ -253,7 +254,7 @@ class GraspActionPlugin(Plugin):
|
|||||||
def action_goal_cb(self):
|
def action_goal_cb(self):
|
||||||
self.elapsed_time = 0.0
|
self.elapsed_time = 0.0
|
||||||
goal = self.action_server.accept_new_goal()
|
goal = self.action_server.accept_new_goal()
|
||||||
self.gripper.set_desired_speed(-0.1)
|
self.gripper.set_desired_speed(-0.1, force=self.force)
|
||||||
|
|
||||||
def update(self):
|
def update(self):
|
||||||
if self.action_server.is_active():
|
if self.action_server.is_active():
|
||||||
|
Loading…
x
Reference in New Issue
Block a user