diff --git a/ur_bringup/launch/ur_common.launch b/ur_bringup/launch/ur_common.launch index cd3b292caa6eb98df20ed788f474bc7fb31d47a1..f2d9e9e6a5e84c0138ec061c5acf87945506e8f5 100644 --- a/ur_bringup/launch/ur_common.launch +++ b/ur_bringup/launch/ur_common.launch @@ -16,6 +16,9 @@ <arg name="min_payload"/> <arg name="max_payload"/> + <!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits --> + <arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> + <!-- copy the specified IP address to be consistant with ROS-Industrial spec. NOTE: The ip address is actually passed to the driver on the command line --> <param name="/robot_ip_address" type="str" value="$(arg robot_ip)"/> @@ -27,6 +30,7 @@ <node name="ur_driver" pkg="ur_driver" type="driver.py" args="$(arg robot_ip) $(arg reverse_port)" output="screen"> <param name="min_payload" type="double" value="$(arg min_payload)"/> <param name="max_payload" type="double" value="$(arg max_payload)"/> + <param name="max_velocity" type="double" value="$(arg max_velocity)"/> </node> <!-- TF Buffer Server --> diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 469e523d2220eb89424f1787ca9e377ff5cab29d..58242044a0ea1978b85afb414f34210a42a3d9a8 100755 --- a/ur_driver/src/ur_driver/driver.py +++ b/ur_driver/src/ur_driver/driver.py @@ -62,6 +62,10 @@ MULT_blend = 1000.0 MULT_analog = 1000000.0 MULT_analog_robotstate = 0.1 +#Max Velocity accepted by ur_driver +MAX_VELOCITY = 10.0 +#Using a very high value in order to not limit execution of trajectories being sent from MoveIt! + #Bounds for SetPayload service MIN_PAYLOAD = 0.0 MAX_PAYLOAD = 1.0 @@ -926,8 +930,10 @@ def main(): rospy.loginfo("No calibration offsets loaded from urdf") # Reads the maximum velocity + # The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits global max_velocity - max_velocity = rospy.get_param("~max_velocity", 2.0) + max_velocity = rospy.get_param("~max_velocity", MAX_VELOCITY) # [rad/s] + rospy.loginfo("Max velocity accepted by ur_driver: %s [rad/s]" % max_velocity) # Reads the minimum payload global min_payload