Skip to content

Commit e8a127f

Browse files
authored
Fix rqt jtc bugs for continuous joints and other minor bugs (#890)
1 parent 925a690 commit e8a127f

File tree

2 files changed

+42
-25
lines changed

2 files changed

+42
-25
lines changed

rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_limits_urdf.py

Lines changed: 35 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,10 @@
1414
# See the License for the specific language governing permissions and
1515
# limitations under the License.
1616

17+
# Code inspired on the joint_state_publisher package by David Lu!!!
18+
# https://github.com/ros/robot_model/blob/indigo-devel/
19+
# joint_state_publisher/joint_state_publisher/joint_state_publisher
20+
1721
# TODO: Use urdf_parser_py.urdf instead. I gave it a try, but got
1822
# Exception: Required attribute not set in XML: upper
1923
# upper is an optional attribute, so I don't understand what's going on
@@ -33,21 +37,24 @@ def callback(msg):
3337
description = msg.data
3438

3539

36-
def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=True):
37-
global description
38-
use_small = use_smallest_joint_limits
39-
use_mimic = True
40-
41-
# Code inspired on the joint_state_publisher package by David Lu!!!
42-
# https://github.com/ros/robot_model/blob/indigo-devel/
43-
# joint_state_publisher/joint_state_publisher/joint_state_publisher
44-
40+
def subscribe_to_robot_description(node, key="robot_description"):
4541
qos_profile = rclpy.qos.QoSProfile(depth=1)
4642
qos_profile.durability = rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL
4743
qos_profile.reliability = rclpy.qos.ReliabilityPolicy.RELIABLE
4844

49-
node.create_subscription(String, "/robot_description", callback, qos_profile)
50-
rclpy.spin_once(node)
45+
node.create_subscription(String, key, callback, qos_profile)
46+
47+
48+
def get_joint_limits(node, use_smallest_joint_limits=True):
49+
global description
50+
use_small = use_smallest_joint_limits
51+
use_mimic = True
52+
53+
count = 0
54+
while description == "" and count < 10:
55+
print("Waiting for the robot_description!")
56+
count += 1
57+
rclpy.spin_once(node, timeout_sec=1.0)
5158

5259
free_joints = {}
5360
dependent_joints = {}
@@ -66,21 +73,27 @@ def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=Tr
6673
name = child.getAttribute("name")
6774
try:
6875
limit = child.getElementsByTagName("limit")[0]
69-
except IndexError:
70-
continue
71-
if jtype == "continuous":
72-
minval = -pi
73-
maxval = pi
74-
else:
7576
try:
7677
minval = float(limit.getAttribute("lower"))
7778
maxval = float(limit.getAttribute("upper"))
7879
except ValueError:
79-
continue
80-
try:
81-
maxvel = float(limit.getAttribute("velocity"))
82-
except ValueError:
83-
continue
80+
if jtype == "continuous":
81+
minval = -pi
82+
maxval = pi
83+
else:
84+
raise Exception(
85+
f"Missing lower/upper position limits for the joint : {name} of type : {jtype} in the robot_description!"
86+
)
87+
try:
88+
maxvel = float(limit.getAttribute("velocity"))
89+
except ValueError:
90+
raise Exception(
91+
f"Missing velocity limits for the joint : {name} of type : {jtype} in the robot_description!"
92+
)
93+
except IndexError:
94+
raise Exception(
95+
f"Missing limits tag for the joint : {name} in the robot_description!"
96+
)
8497
safety_tags = child.getElementsByTagName("safety_controller")
8598
if use_small and len(safety_tags) == 1:
8699
tag = safety_tags[0]

rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929

3030
from .utils import ControllerLister, ControllerManagerLister
3131
from .double_editor import DoubleEditor
32-
from .joint_limits_urdf import get_joint_limits
32+
from .joint_limits_urdf import get_joint_limits, subscribe_to_robot_description
3333
from .update_combo import update_combo
3434

3535
# TODO:
@@ -170,6 +170,9 @@ def __init__(self, context):
170170
self._update_jtc_list_timer.timeout.connect(self._update_jtc_list)
171171
self._update_jtc_list_timer.start()
172172

173+
# subscriptions
174+
subscribe_to_robot_description(self._node)
175+
173176
# Signal connections
174177
w = self._widget
175178
w.enable_button.toggled.connect(self._on_jtc_enabled)
@@ -460,8 +463,9 @@ def _jtc_joint_names(jtc_info):
460463

461464
joint_names = []
462465
for interface in jtc_info.claimed_interfaces:
463-
name = interface.split("/")[0]
464-
joint_names.append(name)
466+
name = interface.split("/")[-2]
467+
if name not in joint_names:
468+
joint_names.append(name)
465469

466470
return joint_names
467471

0 commit comments

Comments
 (0)