Skip to content

Commit

Permalink
Fix rqt jtc bugs for continuous joints and other minor bugs (#890) (#892
Browse files Browse the repository at this point in the history
)

(cherry picked from commit e8a127f)

Co-authored-by: Sai Kishor Kothakota <[email protected]>
  • Loading branch information
mergify[bot] and saikishor authored Dec 8, 2023
1 parent 7d9079b commit 4588cb6
Show file tree
Hide file tree
Showing 2 changed files with 42 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.

# Code inspired on the joint_state_publisher package by David Lu!!!
# https://github.com/ros/robot_model/blob/indigo-devel/
# joint_state_publisher/joint_state_publisher/joint_state_publisher

# TODO: Use urdf_parser_py.urdf instead. I gave it a try, but got
# Exception: Required attribute not set in XML: upper
# upper is an optional attribute, so I don't understand what's going on
Expand All @@ -33,21 +37,24 @@ def callback(msg):
description = msg.data


def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=True):
global description
use_small = use_smallest_joint_limits
use_mimic = True

# Code inspired on the joint_state_publisher package by David Lu!!!
# https://github.com/ros/robot_model/blob/indigo-devel/
# joint_state_publisher/joint_state_publisher/joint_state_publisher

def subscribe_to_robot_description(node, key="robot_description"):
qos_profile = rclpy.qos.QoSProfile(depth=1)
qos_profile.durability = rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL
qos_profile.reliability = rclpy.qos.ReliabilityPolicy.RELIABLE

node.create_subscription(String, "/robot_description", callback, qos_profile)
rclpy.spin_once(node)
node.create_subscription(String, key, callback, qos_profile)


def get_joint_limits(node, use_smallest_joint_limits=True):
global description
use_small = use_smallest_joint_limits
use_mimic = True

count = 0
while description == "" and count < 10:
print("Waiting for the robot_description!")
count += 1
rclpy.spin_once(node, timeout_sec=1.0)

free_joints = {}
dependent_joints = {}
Expand All @@ -66,21 +73,27 @@ def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=Tr
name = child.getAttribute("name")
try:
limit = child.getElementsByTagName("limit")[0]
except IndexError:
continue
if jtype == "continuous":
minval = -pi
maxval = pi
else:
try:
minval = float(limit.getAttribute("lower"))
maxval = float(limit.getAttribute("upper"))
except ValueError:
continue
try:
maxvel = float(limit.getAttribute("velocity"))
except ValueError:
continue
if jtype == "continuous":
minval = -pi
maxval = pi
else:
raise Exception(
f"Missing lower/upper position limits for the joint : {name} of type : {jtype} in the robot_description!"
)
try:
maxvel = float(limit.getAttribute("velocity"))
except ValueError:
raise Exception(
f"Missing velocity limits for the joint : {name} of type : {jtype} in the robot_description!"
)
except IndexError:
raise Exception(
f"Missing limits tag for the joint : {name} in the robot_description!"
)
safety_tags = child.getElementsByTagName("safety_controller")
if use_small and len(safety_tags) == 1:
tag = safety_tags[0]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

from .utils import ControllerLister, ControllerManagerLister
from .double_editor import DoubleEditor
from .joint_limits_urdf import get_joint_limits
from .joint_limits_urdf import get_joint_limits, subscribe_to_robot_description
from .update_combo import update_combo

# TODO:
Expand Down Expand Up @@ -170,6 +170,9 @@ def __init__(self, context):
self._update_jtc_list_timer.timeout.connect(self._update_jtc_list)
self._update_jtc_list_timer.start()

# subscriptions
subscribe_to_robot_description(self._node)

# Signal connections
w = self._widget
w.enable_button.toggled.connect(self._on_jtc_enabled)
Expand Down Expand Up @@ -460,8 +463,9 @@ def _jtc_joint_names(jtc_info):

joint_names = []
for interface in jtc_info.claimed_interfaces:
name = interface.split("/")[0]
joint_names.append(name)
name = interface.split("/")[-2]
if name not in joint_names:
joint_names.append(name)

return joint_names

Expand Down

0 comments on commit 4588cb6

Please sign in to comment.