@@ -92,16 +92,51 @@ class UrDriver
9292 * trajectory forwarding.
9393 * \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
9494 * executed locally on the robot.
95- * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
96- * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
9795 */
9896 UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
9997 const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
10098 std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port = 50001 ,
10199 const uint32_t script_sender_port = 50002 , int servoj_gain = 2000 , double servoj_lookahead_time = 0.03 ,
102100 bool non_blocking_read = false , const std::string& reverse_ip = " " , const uint32_t trajectory_port = 50003 ,
103- const uint32_t script_command_port = 50004 , double force_mode_damping = 0.025 ,
104- double force_mode_gain_scaling = 0.5 );
101+ const uint32_t script_command_port = 50004 );
102+
103+ /* !
104+ * \brief Constructs a new UrDriver object.
105+ * \param robot_ip IP-address under which the robot is reachable.
106+ * \param script_file URScript file that should be sent to the robot.
107+ * \param output_recipe_file Filename where the output recipe is stored in.
108+ * \param input_recipe_file Filename where the input recipe is stored in.
109+ * \param handle_program_state Function handle to a callback on program state changes. For this to
110+ * work, the URScript program will have to send keepalive signals to the \p reverse_port. I no
111+ * keepalive signal can be read, program state will be false.
112+ * \param headless_mode Parameter to control if the driver should be started in headless mode.
113+ * \param tool_comm_setup Configuration for using the tool communication.
114+ * calibration reported by the robot.
115+ * \param reverse_port Port that will be opened by the driver to allow direct communication between the driver
116+ * and the robot controller.
117+ * \param script_sender_port The driver will offer an interface to receive the program's URScript on this port. If
118+ * the robot cannot connect to this port, `External Control` will stop immediately.
119+ * \param non_blocking_read Enable non-blocking mode for read (useful when used with combined_robot_hw)
120+ * \param servoj_gain Proportional gain for arm joints following target position, range [100,2000]
121+ * \param servoj_lookahead_time Time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time
122+ * \param reverse_ip IP address that the reverse_port will get bound to. If not specified, the IP
123+ * address of the interface that is used for connecting to the robot's RTDE port will be used.
124+ * \param trajectory_port Port used for sending trajectory points to the robot in case of
125+ * trajectory forwarding.
126+ * \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
127+ * executed locally on the robot.
128+ * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
129+ * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
130+ */
131+ [[deprecated(" Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has "
132+ " been deprecated. Force mode parameters should be specified with each activiation of force mode, and "
133+ " can be set in the function call to start force mode." )]]
134+ UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
135+ const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
136+ std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port,
137+ const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read,
138+ const std::string& reverse_ip, const uint32_t trajectory_port, const uint32_t script_command_port,
139+ double force_mode_damping, double force_mode_gain_scaling = 0.5 );
105140
106141 /* !
107142 * \brief Constructs a new UrDriver object.
@@ -134,7 +169,7 @@ class UrDriver
134169 */
135170 UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
136171 const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
137- std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = " " ,
172+ std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum,
138173 const uint32_t reverse_port = 50001 , const uint32_t script_sender_port = 50002 , int servoj_gain = 2000 ,
139174 double servoj_lookahead_time = 0.03 , bool non_blocking_read = false , const std::string& reverse_ip = " " ,
140175 const uint32_t trajectory_port = 50003 , const uint32_t script_command_port = 50004 ,
@@ -321,6 +356,67 @@ class UrDriver
321356 */
322357 bool setToolVoltage (const ToolVoltage voltage);
323358
359+ /* !
360+ * \brief Start the robot to be controlled in force mode.
361+ *
362+ * \param task_frame A pose vector that defines the force frame relative to the base frame
363+ * \param selection_vector A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding
364+ * axis of the task frame
365+ * \param wrench 6d vector of forces/torques [x,y,z,rotX,rotY,rotZ] that the robot will apply to its environment. The
366+ * robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have
367+ * no effect for non-compliant axes.
368+ * \param type An integer [1;3] specifying how the robot interprets the force frame.
369+ * 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot
370+ * tcp towards the origin of the force frame
371+ * 2: The force frame is not transformed
372+ * 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector
373+ * onto the x-y plane of the force frame
374+ * \param limits (double) 6d vector. For compliant axes, these values are the maximum allowed tcp speed
375+ * along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis
376+ * between the actual tcp position and the one set by the program
377+ *
378+ * \param damping_factor (double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025
379+ * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
380+ * is no damping, here the robot will maintain the speed.
381+ *
382+ * \returns True, if the write was performed successfully, false otherwise.
383+ */
384+ bool startForceMode (const vector6d_t & task_frame, const vector6uint32_t & selection_vector, const vector6d_t & wrench,
385+ const unsigned int type, const vector6d_t & limits, double damping_factor);
386+
387+ /* !
388+ * \brief Start the robot to be controlled in force mode.
389+ *
390+ * \param task_frame A pose vector that defines the force frame relative to the base frame
391+ * \param selection_vector A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding
392+ * axis of the task frame
393+ * \param wrench 6d vector of forces/torques [x,y,z,rotX,rotY,rotZ] that the robot will apply to its environment. The
394+ * robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have
395+ * no effect for non-compliant axes.
396+ * \param type An integer [1;3] specifying how the robot interprets the force frame.
397+ * 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot
398+ * tcp towards the origin of the force frame
399+ * 2: The force frame is not transformed
400+ * 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector
401+ * onto the x-y plane of the force frame
402+ * \param limits (double) 6d vector. For compliant axes, these values are the maximum allowed tcp speed
403+ * along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis
404+ * between the actual tcp position and the one set by the program
405+ *
406+ * \param damping_factor (double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025
407+ * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
408+ * is no damping, here the robot will maintain the speed.
409+ *
410+ * \param gain_scaling_factor (double) Scales the gain in force mode. scaling parameter in range [0,2], default is
411+ * 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard
412+ * surfaces.
413+ *
414+ * \returns True, if the write was performed successfully, false otherwise.
415+ */
416+ bool startForceMode (const vector6d_t & task_frame, const vector6uint32_t & selection_vector, const vector6d_t & wrench,
417+ const unsigned int type, const vector6d_t & limits, double damping_factor,
418+ double gain_scaling_factor);
419+
324420 /* !
325421 * \brief Start the robot to be controlled in force mode.
326422 *
@@ -342,6 +438,8 @@ class UrDriver
342438 *
343439 * \returns True, if the write was performed successfully, false otherwise.
344440 */
441+ [[deprecated(" Starting force mode without specifying the force mode damping factor and gain scale factor has been "
442+ " deprecated. These values should be given with each function call." )]]
345443 bool startForceMode (const vector6d_t & task_frame, const vector6uint32_t & selection_vector, const vector6d_t & wrench,
346444 const unsigned int type, const vector6d_t & limits);
347445
@@ -500,6 +598,9 @@ class UrDriver
500598 std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> primary_stream_;
501599 std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> secondary_stream_;
502600
601+ double force_mode_gain_scale_factor_ = 0.5 ;
602+ double force_mode_damping_factor_ = 0.025 ;
603+
503604 uint32_t servoj_gain_;
504605 double servoj_lookahead_time_;
505606 std::chrono::milliseconds step_time_;
0 commit comments