Skip to content
Open
Show file tree
Hide file tree
Changes from 18 commits
Commits
Show all changes
38 commits
Select commit Hold shift + click to select a range
69aced1
setting joint_value_target as the current state for the joints that a…
jeferal Sep 1, 2022
5cc2342
implemented remove_joints_from_plan
jeferal Sep 5, 2022
80d1c0a
style
jeferal Sep 5, 2022
8fd40b3
created test for plan_joint_value_target with partial target and move…
jeferal Sep 6, 2022
dea4b58
style
jeferal Sep 6, 2022
9675e55
undo cropping plan
jeferal Sep 26, 2022
4dc9121
style
jeferal Sep 26, 2022
1fcf0ce
implemented reading from set points
jeferal Sep 26, 2022
2d6c9b2
checked underactuation ratio
jeferal Sep 26, 2022
d2b9708
bounded joint limits
jeferal Oct 3, 2022
0e50fa5
removed todo
jeferal Oct 3, 2022
a83b770
created function to bound joint states
jeferal Oct 12, 2022
97ed92c
removed continue
jeferal Oct 12, 2022
b353441
Merge branch 'noetic-devel' into B#SP-376_joints_reseted_when_plannin…
jeferal Oct 12, 2022
0af6674
linter errors
jeferal Oct 12, 2022
9a02700
added public getter to get joint limits
jeferal Oct 12, 2022
6254394
Merge branch 'noetic-devel' into B#SP-376_joints_reseted_when_plannin…
jeferal Oct 14, 2022
480fc1e
added years
jeferal Oct 18, 2022
f298774
small style changes
jeferal Oct 19, 2022
b17bb1a
reformatted checking for underactuated joint
jeferal Oct 31, 2022
c0e9d31
refactored underactuated check
jeferal Oct 31, 2022
fc05a18
fixed issue having j0 in get current set points
jeferal Oct 31, 2022
ee270c0
undid splitting line
jeferal Oct 31, 2022
2303648
extended equations for set points j1, j2 to avoid division by 0
jeferal Nov 2, 2022
90dc1aa
refactored j0, j1 and j2 equations
jeferal Nov 2, 2022
99e816e
renamed variables to be more readable
jeferal Nov 2, 2022
df2c826
fixed comment
jeferal Nov 2, 2022
f09ce7b
Merge branch 'noetic-devel' into B#SP-376_joints_reseted_when_plannin…
Nov 14, 2022
d65af25
modified set point with state if it is far
jeferal Nov 18, 2022
f8d1de5
update set points in case they are far from the current state
jeferal Nov 21, 2022
f23062c
added comments and use execute instead of go
jeferal Nov 21, 2022
d83c462
refactored checking topics subscribed
jeferal Nov 22, 2022
6a09a29
fixed typo
jeferal Nov 22, 2022
0952bd7
lint error
jeferal Nov 22, 2022
5fb64ed
used array instead of dictionary
jeferal Nov 24, 2022
22177ad
fixed mistake in documentation
jeferal Nov 29, 2022
12e6217
changed list name
jeferal Dec 13, 2022
543eb52
fixed typo
jeferal Dec 13, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
209 changes: 203 additions & 6 deletions sr_robot_commander/src/sr_robot_commander/sr_robot_commander.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

# Copyright 2015 Shadow Robot Company Ltd.
# Copyright 2015-2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -15,27 +15,31 @@
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't need this anymore

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If I'm not wrong, this repo still has the master branch of the linter , so if I remove this line, the tests might fail

from __future__ import division
import threading

import rospy
from actionlib import SimpleActionClient
from control_msgs.msg import FollowJointTrajectoryAction, \
FollowJointTrajectoryGoal
FollowJointTrajectoryGoal, JointControllerState
from moveit_commander import MoveGroupCommander, RobotCommander, \
PlanningSceneInterface
from moveit_msgs.msg import RobotTrajectory, PositionIKRequest
from sensor_msgs.msg import JointState
from control_msgs.msg import JointTrajectoryControllerState
import geometry_msgs.msg
from sr_robot_msgs.srv import RobotTeachMode, RobotTeachModeRequest, \
RobotTeachModeResponse

from xml.dom import minidom

from moveit_msgs.srv import GetPositionIK
from moveit_msgs.srv import ListRobotStatesInWarehouse as ListStates
from moveit_msgs.srv import GetRobotStateFromWarehouse as GetState
from moveit_msgs.msg import OrientationConstraint, Constraints
from moveit_msgs.msg import OrientationConstraint, Constraints, RobotState

from trajectory_msgs.msg import JointTrajectoryPoint, JointTrajectory
from math import radians
from math import radians, pi

from moveit_msgs.srv import GetPositionFK
from std_msgs.msg import Header
Expand Down Expand Up @@ -101,16 +105,63 @@ def __init__(self, name):

controller_list_param = rospy.get_param("/move_group/controller_list")

robot_description = rospy.get_param("/robot_description")
self._joint_limits = dict()
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

better to have this self._joint_limits = {} to be compliant with the new linter (you have also a dictionary init below done with {} style :)

self._read_joint_limits(robot_description)

# create dictionary with name of controllers and corresponding joints
self._controllers = {item["name"]: item["joints"] for item in controller_list_param}

self._set_up_action_client(self._controllers)

self._set_points_lock = threading.Lock()
self._are_set_points_ready = False
self._set_points_cv = threading.Condition()
self._set_points = {}

self._set_up_set_points_subscribers(self._controllers)

self.tf_buffer = tf2_ros.Buffer()
self.listener = tf2_ros.TransformListener(self.tf_buffer)

threading.Thread(None, rospy.spin)

self._wait_for_set_points()

def _read_joint_limits(self, robot_description):
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this is supposed to happen only once right? Maybe would be better to rename it to something like _initialize_joint_limits and have then a getter like get_joint_limits (returning self._joint_limits)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

which seems you have done below :) skip the getter part of the comment :)

robot_dom = minidom.parseString(robot_description)
robot = robot_dom.getElementsByTagName('robot')[0]

for child in robot.childNodes:
if child.nodeType is child.TEXT_NODE:
continue
if child.localName == 'joint':
jtype = child.getAttribute('type')
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe joint_type instead jtype? same in 144

if jtype in ['fixed', 'floating', 'planar']:
continue
name = child.getAttribute('name')

if jtype == 'continuous':
minval = -pi
maxval = pi
else:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what is the joint_type passed in this else?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ok, thanks

can you then just move the name = child.getAttribute('name') before the first 'if' to slightly increase readability?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the attribute name seems to be particular for nodes of type joint

try:
limit = child.getElementsByTagName('limit')[0]
minval = float(limit.getAttribute('lower'))
maxval = float(limit.getAttribute('upper'))
except Exception as exception:
rospy.logwarn(f"{exception}: {name} is not fixed, nor continuous, \
but limits are not specified!")
continue
self._joint_limits.update({name: (minval, maxval)})

def get_joint_limits(self):
"""
@return - dictionary mapping joint names with a tuple containing the lower limit
and the upper limit of a joint
"""
return self._joint_limits

def _is_trajectory_valid(self, trajectory, required_keys):
if type(trajectory) != list:
rospy.logerr("Trajectory is not a list of waypoints")
Expand Down Expand Up @@ -259,7 +310,10 @@ def move_to_joint_value_target(self, joint_states, wait=True,
if angle_degrees:
joint_states_cpy.update((joint, radians(i))
for joint, i in joint_states_cpy.items())
self._move_group_commander.set_start_state_to_current_state()
set_points, move_group_robot_state = self.get_current_set_points()
self._move_group_commander.set_start_state(move_group_robot_state)
set_points = self._bound_state(set_points)
self._move_group_commander.set_joint_value_target(set_points)
self._move_group_commander.set_joint_value_target(joint_states_cpy)
self._move_group_commander.go(wait=wait)
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looks like go function uses the current state internally, I tried to find the line of code that does that, but I could not. By performing tests, I could not reproduce the problem on planning when an object is grasped and that makes me think that is using the current state instead of the state set when using .set_start_satate


Expand All @@ -277,14 +331,18 @@ def plan_to_joint_value_target(self, joint_states, angle_degrees=False, custom_s
@return - motion plan (RobotTrajectory msg) that contains the trajectory to the set goal state.
"""
joint_states_cpy = copy.deepcopy(joint_states)
set_points, robot_state = self.get_current_set_points()

if angle_degrees:
joint_states_cpy.update((joint, radians(i))
for joint, i in joint_states_cpy.items())
if custom_start_state is None:
self._move_group_commander.set_start_state_to_current_state()
self._move_group_commander.set_start_state(robot_state)
else:
self._move_group_commander.set_start_state(custom_start_state)

set_points_bounded = self._bound_state(set_points)
self._move_group_commander.set_joint_value_target(set_points_bounded)
self._move_group_commander.set_joint_value_target(joint_states_cpy)
self.__plan = self._move_group_commander.plan()[CONST_TUPLE_TRAJECTORY_INDEX]
return self.__plan
Expand Down Expand Up @@ -464,6 +522,75 @@ def get_current_state_bounded(self):
def get_robot_state_bounded(self):
return self._move_group_commander._g.get_current_state_bounded()

@staticmethod
def _bound_joint(joint_value, joint_limits):
"""
Forces a joint value to be within the given joint limits
@joint_value - Value of the joint to be bounded
@joint_limits - Tuple with the lower limit and upper limit of the joint
@return - Joint value within the given joints
"""
if joint_value < joint_limits[0]:
joint_value = joint_limits[0]
elif joint_value > joint_limits[1]:
joint_value = joint_limits[1]
return joint_value

def _bound_state(self, joint_states):
"""
Bounds the joint states within the limits of the joints
@param joint_states - It can be of type dict or RobotState. This param should contain the joints to be bounded
within their limits
@return - The joint states updated with the joint poisitions bounded
"""
if type(joint_states) == dict:
for joint in joint_states:
joint_states[joint] = self._bound_joint(joint_states[joint],
self._joint_limits[joint])

elif type(joint_states) == RobotState:
for i in range(0, len(joint_states.joint_state.name)):
joint_states.joint_state.position[i] = \
self._bound_joint(joint_states.joint_state.position[i],
self._joint_limits[joint_states.joint_state.name[i]])

return joint_states

def get_current_set_points(self):
"""
Reads from the set points
@return - Dictionary which contains the set points of the joints that belong to the move group
"""
with self._set_points_lock:
raw_set_points = copy.deepcopy(self._set_points)

current_state = self.get_current_state()
set_points = {}

for joint in raw_set_points:
if "J0" in joint:
# Get j1 j2 ratio from current state
underactuation_ratio = current_state[f"{joint[:-2]}J1"]/current_state[f"{joint[:-2]}J2"]
ratio_part = raw_set_points[joint]/(underactuation_ratio+1)
set_point_j1 = underactuation_ratio*ratio_part
set_point_j2 = ratio_part
set_points.update({f"{joint[:-2]}J1": set_point_j1})
set_points.update({f"{joint[:-2]}J2": set_point_j2})
elif joint[5:] not in ["J1", "J2"] or joint[3:-2] in ["WR", "TH"]:
set_points.update({joint: raw_set_points[joint]})

joint_state = JointState()
joint_state.header = Header()
joint_state.header.stamp = rospy.Time.now()
for joint in set_points:
joint_state.name.append(joint)
joint_state.position.append(set_points[joint])

move_group_robot_state = RobotState()
move_group_robot_state.joint_state = joint_state

return set_points, move_group_robot_state

def move_to_named_target(self, name, wait=True):
"""
Set target of the robot's links and moves to it
Expand Down Expand Up @@ -770,6 +897,35 @@ def _joint_states_callback(self, joint_state):
self._joints_effort = {n: v for n, v in
zip(joint_state.name, joint_state.effort)}
Comment on lines 976 to 977
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

side note -> this can be just self._joints_effort = {zip(joint_state.name, joint_state.effort)}


def _set_up_set_points_subscribers(self, controllers_list):
"""
Sets up the required subscribers to read from the set points of each given controller
@param controller_list - Dictionary mapping a trajectory controller with the list of the joints it has
"""
# Get joint names of the group
joint_names_group = self._move_group_commander.get_active_joints()
topics_subscribed = []

for controller_name in controllers_list.keys():
for joint_name in joint_names_group:
if joint_name in controllers_list[controller_name]:
topic_name = f"/{controller_name}/state"
if topic_name not in topics_subscribed:
rospy.Subscriber(topic_name, JointTrajectoryControllerState, self._set_point_cb, queue_size=1)
topics_subscribed.append(topic_name)

for joint_name in joint_names_group:
joint_member = joint_name[3:-2]
joint_number = joint_name[5:]
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add as comment the structure of joint_name, or use any() in the if below if you can :)

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe a regex with a substring match?

if joint_number in ["J1", "J2"] and joint_member not in ["WR", "TH"]:
topic_name = f"/sh_{joint_name.lower()[0:5]}j0_position_controller/state"
rospy.Subscriber(topic_name,
JointControllerState,
self._set_point_j0_cb, f"{joint_name[0:5]}J0",
queue_size=1)
joint_names_group.remove(f"{joint_name[0:5]}J1")
joint_names_group.remove(f"{joint_name[0:5]}J2")

def _set_up_action_client(self, controller_list):
"""
Sets up an action client to communicate with the trajectory controller.
Expand Down Expand Up @@ -852,6 +1008,47 @@ def _call_action(self, goals):
self._clients[client].send_goal(
goals[client], lambda terminal_state, result: self._action_done_cb(client, terminal_state, result))

def _set_point_cb(self, msg):
"""
Updates the dictionary mapping joint names with their desired position in the trajectory controllers
@param msg - ROS message of type JointTrajectoryControllerState
"""
joint_names_group = self._move_group_commander.get_active_joints()
with self._set_points_lock:
for i in range(0, len(msg.joint_names)):
if msg.joint_names[i] not in joint_names_group:
continue
self._set_points.update({msg.joint_names[i]: msg.desired.positions[i]})
if not self._are_set_points_ready:
with self._set_points_cv:
joint_names_group = self._move_group_commander.get_active_joints()
for joint_name in joint_names_group:
if joint_name[5:] in ["J1", "J2"] and joint_name[3:-2] not in ["WR", "TH"]:
joint_names_group.append(f"{joint_name[0:5]}J0")
for joint_name in joint_names_group:
if joint_name not in self._set_points.keys():
break
else:
self._are_set_points_ready = True
self._set_points_cv.notifyAll()

def _set_point_j0_cb(self, msg, joint_name):
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As mentioned before, not really sure if we need to know the J0 goals at all.
Given that we know the J1 and J2 goals (because this whole RobotCommander relies on having a JointTrajectoryposition controller running), maybe we don't need this?

Copy link
Contributor Author

@jeferal jeferal Dec 13, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we took the decision of listening to J0's set points because the J1 and J2 set points because of the underactuation might be far from the real state and also outside of the joint limits. For instance, when the set point of FFJ2 is 90deg and the set point of FFJ1 is ~60deg I find this:
image
If I directly set these set points as the target state when planning, moveit will throw the error: target state is outside of the bounds. I think this also depends on a tolerance that is set through this method.
However, since we also encountered the "problem" of the set points being far from the state when grasping an object and added the "fix" of checking if the set point is far from the state and if it is, use the state then listening to j0's might not be useful.
I also agree that perhaps we should rethink of this whole architecture again.

"""
Updates the dictionary mapping joint names with their desired position in the trajectory controllers
This callback is associated to the position controller of j0
@param msg - ROS message of type JointControllerState
"""
with self._set_points_lock:
self._set_points.update({joint_name: msg.set_point})

def _wait_for_set_points(self):
"""
Waits until the set points variable has been updated with all joints
"""
if not self._are_set_points_ready:
with self._set_points_cv:
self._set_points_cv.wait()

def run_joint_trajectory_unsafe(self, joint_trajectory, wait=True):
"""
Moves robot through all joint states with specified timeouts.
Expand Down
34 changes: 33 additions & 1 deletion sr_robot_commander/test/test_robot_commander.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

# Copyright 2021 Shadow Robot Company Ltd.
# Copyright 2021, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand Down Expand Up @@ -53,7 +53,15 @@
'ra_shoulder_lift_joint': -1.37, 'ra_wrist_1_joint': -0.52,
'ra_wrist_2_joint': 1.57, 'ra_wrist_3_joint': 0.00}

CONST_PARTIAL_TARGET = {'ra_shoulder_pan_joint': 0.2, 'ra_wrist_1_joint': -0.52,
'ra_wrist_2_joint': 1.57}

CONST_FULL_TARGET = {'ra_shoulder_pan_joint': 0.2, 'ra_elbow_joint': 2.00,
'ra_shoulder_lift_joint': -1.25, 'ra_wrist_1_joint': -0.52,
'ra_wrist_2_joint': 1.57, 'ra_wrist_3_joint': 3.14}

TOLERANCE_UNSAFE = 0.04
TOLERANCE_SAFE = 0.01
PLANNING_ATTEMPTS = 5


Expand Down Expand Up @@ -146,6 +154,12 @@ def compare_poses(self, pose1, pose2, position_threshold=0.02, orientation_thres
return True
return False

def compare_joint_positions(self, joint_configuration_1, joint_configuration_2, tolerance=0.01):
for key in joint_configuration_1.keys():
if abs(joint_configuration_1[key] - joint_configuration_2[key]) > tolerance:
return False
return True

def test_get_and_set_planner_id(self):
prev_planner_id = self.robot_commander._move_group_commander.get_planner_id()
test_planner_id = "RRTstarkConfigDefault"
Expand Down Expand Up @@ -210,6 +224,24 @@ def test_plan_to_joint_value_target(self):
custom_start_state=None)
self.assertIsInstance(plan, RobotTrajectory)

def test_plan_to_joint_value_target_and_execute_partial(self):
self.reset_to_home()
self.robot_commander._move_group_commander.set_joint_value_target([0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
plan = self.robot_commander.plan_to_joint_value_target(CONST_PARTIAL_TARGET, angle_degrees=False,
custom_start_state=None)
self.robot_commander.execute_plan(plan)
self.assertTrue(self.compare_joint_positions(self.robot_commander.get_current_state(),
CONST_FULL_TARGET,
tolerance=TOLERANCE_SAFE))

def test_move_to_joint_value_target_partial(self):
self.reset_to_home()
self.robot_commander._move_group_commander.set_joint_value_target([0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
self.robot_commander.move_to_joint_value_target(CONST_PARTIAL_TARGET, wait=True)
self.assertTrue(self.compare_joint_positions(self.robot_commander.get_current_state(),
CONST_FULL_TARGET,
tolerance=TOLERANCE_SAFE))

def test_execute(self):
self.reset_to_home()
self.robot_commander.plan_to_joint_value_target(CONST_EXAMPLE_TARGET, angle_degrees=False,
Expand Down