You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Implemented spline interpolation in joint space (#543)
* Added service to activate or deactivate spline interpolation
* Added velocities to test move function in order to force cubic spline interpolation
* Default to using spline interpolation when doing trajectory forwarding.
I think this approach is superior to hardcoding a blend radius with MoveJ
commands. This way we will result in a path that is closer to the one planned
by MoveIt!
* Position only spline interpolation got explicitly removed.
---------
Co-authored-by: Felix Exner <[email protected]>
<argname="headless_mode"default="false"doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
26
26
<argname="ur_hardware_interface_node_required"default="true"doc="Shut down ros environment if ur_hardware_interface-node dies."/>
27
+
<argname="use_spline_interpolation"default="true"doc="True if splines should be used as interpolation on the robot controller when forwarding trajectory, if false movej or movel commands are used"/>
Copy file name to clipboardExpand all lines: ur_robot_driver/launch/ur_control.launch
+2Lines changed: 2 additions & 0 deletions
Original file line number
Diff line number
Diff line change
@@ -33,6 +33,7 @@
33
33
<argname="servoj_gain"default="2000"doc="Specify gain for servoing to position in joint space. A higher gain can sharpen the trajectory."/>
34
34
<argname="servoj_lookahead_time"default="0.03"doc="Specify lookahead time for servoing to position in joint space. A longer lookahead time can smooth the trajectory."/>
35
35
<argname="ur_hardware_interface_node_required"default="true"doc="Shut down ros environment if ur_hardware_interface-node dies."/>
36
+
<argname="use_spline_interpolation"default="true"doc="True if splines should be used as interpolation on the robot controller when forwarding trajectory, if false movej or movel commands are used"/>
0 commit comments