@@ -264,3 +264,79 @@ Implementation details / dataflow
264264* When the hardware reports that execution has been aborted (The ``passthrough_trajectory_abort ``
265265 command interface), the action will be aborted.
266266* When the action is preempted, execution on the hardware is preempted.
267+
268+ .. _force_mode_controller :
269+
270+ ur_controllers/ForceModeController
271+ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
272+
273+ This controller activates the robot's *Force Mode *. This allows direct force control running on the
274+ robot control box. This controller basically interfaces the URScript function ``force_mode(...) ``.
275+
276+ Force mode can be combined with (and only with) the :ref: `passthrough trajectory controller
277+ <passthrough_trajectory_controller>` in order to execute motions under a given force constraints.
278+
279+ .. note ::
280+ This is not an admittance controller, as given force constraints in a certain Cartesian
281+ dimension will overwrite the motion commands in that dimension. E.g. when specifying a certain
282+ force in the base frame's ``z `` direction, any motion resulting from the move command in the
283+ base frame's ``z `` axis will not be executed.
284+
285+ Parameters
286+ """"""""""
287+
288+ +----------------------------------+--------+---------------+---------------------------------------------------------------------+
289+ | Parameter name | Type | Default value | Description |
290+ | | | | |
291+ +----------------------------------+--------+---------------+---------------------------------------------------------------------+
292+ | ``tf_prefix `` | string | <empty> | Urdf prefix of the corresponding arm |
293+ +----------------------------------+--------+---------------+---------------------------------------------------------------------+
294+ | ``check_io_successful_retries `` | int | 10 | Amount of retries for checking if setting force_mode was successful |
295+ +----------------------------------+--------+---------------+---------------------------------------------------------------------+
296+
297+ Service interface / usage
298+ """""""""""""""""""""""""
299+
300+ The controller provides two services: One for activating force_mode and one for leaving it. To use
301+ those services, the controller has to be in ``active `` state.
302+
303+ * ``~/stop_force_mode [std_srvs/srv/Trigger] ``: Stop force mode
304+ * ``~/start_force_mode [ur_msgs/srv/SetForceMode] ``: Start force mode
305+
306+ In ``ur_msgs/srv/SetForceMode `` the fields have the following meanings:
307+
308+ task_frame
309+ All information (selection vector, wrench, limits, etc) will be considered to be relative
310+ to that pose. The pose's frame_id can be anything that is transformable to the robot's
311+ ``base `` frame.
312+ selection_vector_<x,y,z,rx,ry,rz>
313+ 1 means that the robot will be compliant in the corresponding axis of the task frame.
314+ wrench
315+ The forces/torques the robot will apply to its environment. The robot adjusts its position
316+ along/about compliant axis in order to achieve the specified force/torque. Values have no effect for non-
317+ compliant axes.
318+ Actual wrench applied may be lower than requested due to joint safety limits.
319+ type
320+ An integer [1;3] specifying how the robot interprets the force frame
321+
322+ 1
323+ The force frame is transformed in a way such that its y-axis is aligned with a vector pointing
324+ from the robot tcp towards the origin of the force frame.
325+ 2
326+ The force frame is not transformed.
327+ 3
328+ The force frame is transformed in a way such that its x-axis is the projection of the robot tcp
329+ velocity vector onto the x-y plane of the force frame.
330+ speed_limits
331+ Maximum allowed tcp speed (relative to the task frame). This is **only relevant for axes marked as
332+ compliant ** in the selection_vector.
333+ deviation_limits
334+ For **non-compliant axes **, these values are the maximum allowed deviation along/about an axis
335+ between the actual tcp position and the one set by the program.
336+ damping_factor
337+ Force mode damping factor. Sets the damping parameter in force mode. In range [0;1], default value is 0.025
338+ A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
339+ is no damping, here the robot will maintain the speed.
340+ gain_scaling
341+ Force mode gain scaling factor. Scales the gain in force mode. scaling parameter is in range [0;2], default is 0.5.
342+ A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard surfaces.
0 commit comments