|
| 1 | +#!/usr/bin/env python |
| 2 | +import rospy, os |
| 3 | +import numpy as np |
| 4 | +# Actionlib |
| 5 | +from actionlib import SimpleActionServer |
| 6 | +from robotiq_msgs.msg import ( |
| 7 | + CModelCommand, |
| 8 | + CModelStatus, |
| 9 | + CModelCommandAction, |
| 10 | + CModelCommandFeedback, |
| 11 | + CModelCommandResult, |
| 12 | +) |
| 13 | + |
| 14 | +def read_parameter(name, default): |
| 15 | + if not rospy.has_param(name): |
| 16 | + rospy.logwarn('Parameter [%s] not found, using default: %s' % (name, default)) |
| 17 | + return rospy.get_param(name, default) |
| 18 | + |
| 19 | + |
| 20 | +class CModelActionController(object): |
| 21 | + def __init__(self, activate=True): |
| 22 | + self._ns = rospy.get_namespace() |
| 23 | + # Read configuration parameters |
| 24 | + self._fb_rate = read_parameter(self._ns + 'gripper_action_controller/publish_rate', 60.0) |
| 25 | + self._min_gap = read_parameter(self._ns + 'gripper_action_controller/min_gap', 0.0) |
| 26 | + self._max_gap = read_parameter(self._ns + 'gripper_action_controller/max_gap', 0.085) |
| 27 | + self._min_speed = read_parameter(self._ns + 'gripper_action_controller/min_speed', 0.013) |
| 28 | + self._max_speed = read_parameter(self._ns + 'gripper_action_controller/max_speed', 0.1) |
| 29 | + self._min_force = read_parameter(self._ns + 'gripper_action_controller/min_force', 40.0) |
| 30 | + self._max_force = read_parameter(self._ns + 'gripper_action_controller/max_force', 100.0) |
| 31 | + # Configure and start the action server |
| 32 | + self._status = CModelStatus() |
| 33 | + self._name = self._ns + 'gripper_action_controller' |
| 34 | + self._server = SimpleActionServer(self._name, CModelCommandAction, execute_cb=self._execute_cb, auto_start = False) |
| 35 | + rospy.Subscriber('status', CModelStatus, self._status_cb) |
| 36 | + self._cmd_pub = rospy.Publisher('command', CModelCommand, queue_size=3) |
| 37 | + working = True |
| 38 | + if activate and not self._ready(): |
| 39 | + rospy.sleep(2.0) |
| 40 | + working = self._activate() |
| 41 | + if not working: |
| 42 | + return |
| 43 | + self._server.start() |
| 44 | + rospy.loginfo(rospy.loginfo('%s: Started' % self._name)) |
| 45 | + |
| 46 | + def _preempt(self): |
| 47 | + self._stop() |
| 48 | + rospy.loginfo('%s: Preempted' % self._name) |
| 49 | + self._server.set_preempted() |
| 50 | + |
| 51 | + def _status_cb(self, msg): |
| 52 | + self._status = msg |
| 53 | + |
| 54 | + def _execute_cb(self, goal): |
| 55 | + success = True |
| 56 | + # Check that the gripper is active. If not, activate it. |
| 57 | + if not self._ready(): |
| 58 | + if not self._activate(): |
| 59 | + rospy.logwarn('%s could not accept goal because the gripper is not yet active' % self._name) |
| 60 | + return |
| 61 | + # check that preempt has not been requested by the client |
| 62 | + if self._server.is_preempt_requested(): |
| 63 | + self._preempt() |
| 64 | + return |
| 65 | + # Send the goal to the gripper and feedback to the action client |
| 66 | + rate = rospy.Rate(self._fb_rate) |
| 67 | + rospy.loginfo('%s: Moving gripper to position: %.3f ' % (self._name, goal.position)) |
| 68 | + feedback = CModelCommandFeedback() |
| 69 | + while not self._reached_goal(goal.position): |
| 70 | + self._goto_position(goal.position, goal.velocity, goal.force) |
| 71 | + if rospy.is_shutdown() or self._server.is_preempt_requested(): |
| 72 | + self._preempt() |
| 73 | + return |
| 74 | + feedback.position = self._get_position() |
| 75 | + feedback.stalled = self._stalled() |
| 76 | + feedback.reached_goal = self._reached_goal(goal.position) |
| 77 | + self._server.publish_feedback(feedback) |
| 78 | + rate.sleep() |
| 79 | + if self._stalled(): |
| 80 | + break |
| 81 | + rospy.loginfo('%s: Succeeded' % self._name) |
| 82 | + result = CModelCommandResult() |
| 83 | + result.position = self._get_position() |
| 84 | + result.stalled = self._stalled() |
| 85 | + result.reached_goal = self._reached_goal(goal.position) |
| 86 | + self._server.set_succeeded(result) |
| 87 | + |
| 88 | + def _activate(self, timeout=5.0): |
| 89 | + command = CModelCommand(); |
| 90 | + command.rACT = 1 |
| 91 | + command.rGTO = 1 |
| 92 | + command.rSP = 255 |
| 93 | + command.rFR = 150 |
| 94 | + start_time = rospy.get_time() |
| 95 | + while not self._ready(): |
| 96 | + if rospy.is_shutdown(): |
| 97 | + self._preempt() |
| 98 | + return False |
| 99 | + if rospy.get_time() - start_time > timeout: |
| 100 | + rospy.logwarn('Failed to activated gripper in ns [%s]' % (self._ns)) |
| 101 | + return False |
| 102 | + self._cmd_pub.publish(command) |
| 103 | + rospy.sleep(0.1) |
| 104 | + rospy.loginfo('Successfully activated gripper in ns [%s]' % (self._ns)) |
| 105 | + return True |
| 106 | + |
| 107 | + def _get_position(self): |
| 108 | + gPO = self._status.gPO |
| 109 | + pos = np.clip((self._max_gap - self._min_gap)/(-230.)*(gPO-230.), self._min_gap, self._max_gap) |
| 110 | + return pos |
| 111 | + |
| 112 | + def _goto_position(self, pos, vel, force): |
| 113 | + """ |
| 114 | + Goto position with desired force and velocity |
| 115 | + @type pos: float |
| 116 | + @param pos: Gripper width in meters |
| 117 | + @type vel: float |
| 118 | + @param vel: Gripper speed in m/s |
| 119 | + @type force: float |
| 120 | + @param force: Gripper force in N |
| 121 | + """ |
| 122 | + command = CModelCommand() |
| 123 | + command.rACT = 1 |
| 124 | + command.rGTO = 1 |
| 125 | + command.rPR = int(np.clip((-230)/(self._max_gap - self._min_gap) * (pos - self._min_gap) + 230., 0, 230)) |
| 126 | + command.rSP = int(np.clip((255)/(self._max_speed - self._min_speed) * (vel - self._min_speed), 0, 255)) |
| 127 | + command.rFR = int(np.clip((255)/(self._max_force - self._min_force) * (force - self._min_force), 0, 255)) |
| 128 | + self._cmd_pub.publish(command) |
| 129 | + |
| 130 | + def _moving(self): |
| 131 | + return self._status.gGTO == 1 and self._status.gOBJ == 0 |
| 132 | + |
| 133 | + def _reached_goal(self, goal, tol = 0.003): |
| 134 | + return (abs(goal - self._get_position()) < tol) |
| 135 | + |
| 136 | + def _ready(self): |
| 137 | + return self._status.gSTA == 3 and self._status.gACT == 1 |
| 138 | + |
| 139 | + def _stalled(self): |
| 140 | + return self._status.gOBJ == 1 or self._status.gOBJ == 2 |
| 141 | + |
| 142 | + def _stop(self): |
| 143 | + command = CModelCommand() |
| 144 | + command.rACT = 1 |
| 145 | + command.rGTO = 0 |
| 146 | + self._cmd_pub.publish(command) |
| 147 | + rospy.loginfo('Stopping gripper in ns [%s]' % (self._ns)) |
| 148 | + |
| 149 | + |
| 150 | +if __name__ == '__main__': |
| 151 | + node_name = os.path.splitext(os.path.basename(__file__))[0] |
| 152 | + rospy.init_node(node_name) |
| 153 | + rospy.loginfo('Starting [%s] node' % node_name) |
| 154 | + cmodel_server = CModelActionController() |
| 155 | + rospy.spin() |
| 156 | + rospy.loginfo('Shuting down [%s] node' % node_name) |
0 commit comments