Can I use this only in simulation?
Closed this issue · 1 comments
I'm trying to use this package only in simulation, I don't have the real gripper. But I have an error that says:
from pymodbus.client.sync import ModbusSerialClient
ImportError: No module named pymodbus.client.sync
The question is, can I use this package without having the real gripper?
Sorry for the late response, yes you can. Simulation is one of the features of the package.
The simulated gripper driver handles the fake operation of the gripper and the update of the joint_state
variables accordingly:
Lines 418 to 542 in 42b0a40
class Robotiq2FingerSimulatedGripperDriver: | |
""" | |
This class represents an abstraction of a gripper driver for a SIMULATED gripper, | |
by simulating the operation/response of the gripper to a given command and the publishing | |
of the simulated gripper joint position to the `/joint_state` topic. | |
Args: | |
stroke: Stroke of the gripper you are using, should be `0.085` or `0.140`. | |
finger_joint: Name of the URDF joint to publish on the `/joint_state` topic. | |
Attributes: | |
is_ready: Boolean indicating gripper is ready to take commands. | |
_gripper_joint_state_pub: Ros publisher for the `/joint_state` topic. | |
_current_joint_pos: [radians] Position of the simulated joint in radians. | |
_current_goal: Instance of `RobotiqGripperCommand` message holding the latest user command. | |
""" | |
def __init__(self, stroke=0.085, joint_name='finger_joint'): | |
self._stroke = stroke | |
self._joint_name = joint_name | |
self._current_joint_pos = 0.0 | |
self._prev_time = rospy.get_time() | |
self._current_goal = CommandRobotiqGripperGoal() | |
self._current_goal.position = self._stroke | |
self._gripper_joint_state_pub = rospy.Publisher("/joint_states" , JointState, queue_size=10) | |
self.is_ready = True | |
self._is_moving = False | |
self._max_joint_limit = 0.8 | |
if( self._stroke == 0.140 ): | |
self._max_joint_limit = 0.7 | |
def update_driver(self): | |
""" | |
Public function simulating the gripper state change given the current gripper command and the time | |
difference between the last call to this function. | |
""" | |
delta_time = rospy.get_time() - self._prev_time | |
linear_position_goal = self._current_goal.position #[mm] | |
joint_goal = self.from_distance_to_radians(linear_position_goal) #[rad] | |
position_increase = (delta_time * self._current_goal.speed) * (self._max_joint_limit/self._stroke) | |
if( abs(joint_goal - self._current_joint_pos) > position_increase ): | |
self._current_joint_pos += position_increase if (joint_goal - self._current_joint_pos) > 0 else -position_increase | |
self._is_moving = True | |
else: | |
self._current_joint_pos = joint_goal | |
self._is_moving = False | |
js = self._update_gripper_joint_state() | |
self._gripper_joint_state_pub.publish(js) | |
self._prev_time = rospy.get_time() | |
def update_gripper_command(self, goal_command): | |
""" | |
Updates the driver internal goal/setpoint, which will be use to command the robotiq gripper/ | |
Args: | |
goal_command: Instance of `robotiq_2f_gripper_msgs/RobotiqGripperCommand` message, holding the most recent | |
user provided command parameters. See the message declaration for fields description | |
""" | |
self._current_goal = goal_command | |
self._current_goal.position = self._clamp_position(goal_command.position) | |
self._current_goal.speed = self._clamp_speed(goal_command.speed) | |
def get_current_gripper_status(self): | |
""" | |
Public function to obtain the current gripper status. | |
Returns: Instance of `robotiq_2f_gripper_msgs/RobotiqGripperStatus` message. See the message declaration for fields description | |
""" | |
status = RobotiqGripperStatus() | |
status.header.stamp = rospy.get_rostime() | |
status.header.seq = 0 | |
status.is_ready = True | |
status.is_reset = False | |
status.is_moving = self._is_moving | |
status.obj_detected = False | |
status.fault_status = False | |
status.position = self.from_radians_to_distance(self._current_joint_pos) #[mm] | |
status.requested_position = self._current_goal.position #[mm] | |
status.current = 0.0 | |
return status | |
def get_current_joint_position(self): | |
return self._current_joint_pos | |
def from_distance_to_radians(self, linear_pose ): | |
""" | |
Private helper function to convert a command in meters to radians (joint value) | |
""" | |
return np.clip(self._max_joint_limit - ((self._max_joint_limit/self._stroke) * linear_pose), 0.0, self._max_joint_limit) | |
def from_radians_to_distance(self, joint_pose): | |
""" | |
Private helper function to convert a joint position in radians to meters (distance between fingers) | |
""" | |
return np.clip(self._stroke - ((self._stroke/self._max_joint_limit) * joint_pose), 0.0, self._max_joint_limit) | |
def _update_gripper_joint_state(self): | |
""" | |
Private helper function to create a JointState message with the current gripper joint position | |
""" | |
js = JointState() | |
js.header.frame_id = '' | |
js.header.stamp = rospy.get_rostime() | |
js.header.seq = 0 | |
js.name = [self._joint_name] | |
pos = np.clip( self._current_joint_pos, 0.0, self._max_joint_limit) | |
js.position = [pos] | |
js.velocity = [self._current_goal.speed] | |
self._prev_joint_pos = pos | |
return js | |
def _clamp_position(self,cmd): | |
if (cmd <= 0.0): | |
cmd = 0.0 | |
elif (cmd >= self._stroke): | |
cmd = self._stroke | |
return cmd | |
def _clamp_speed(self,cmd): | |
if (cmd < 0.0): | |
cmd = 0.01 | |
elif (cmd > 0.101): | |
cmd = 0.1 | |
return cmd |
Also, check the node robotiq_2f_action_server
arguments, there you have a parameter called sim
, which internally chooses to call the real driver controller or a simulated one.