Skip to content

Commit 1058313

Browse files
authored
Merge pull request #1 from pazeshun/first-point-commanded
Change first point in trajectory to commanded position
2 parents 872afc4 + 5a8767d commit 1058313

2 files changed

Lines changed: 43 additions & 2 deletions

File tree

src/baxter_interface/limb.py

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
from baxter_core_msgs.msg import (
4444
JointCommand,
4545
EndpointState,
46+
SEAJointState,
4647
)
4748
from baxter_interface import settings
4849

@@ -67,6 +68,7 @@ def __init__(self, limb):
6768
self._joint_angle = dict()
6869
self._joint_velocity = dict()
6970
self._joint_effort = dict()
71+
self._joint_commanded_angle = dict()
7072
self._cartesian_pose = dict()
7173
self._cartesian_velocity = dict()
7274
self._cartesian_effort = dict()
@@ -115,6 +117,13 @@ def __init__(self, limb):
115117
queue_size=1,
116118
tcp_nodelay=True)
117119

120+
_sea_joint_state_sub = rospy.Subscriber(
121+
ns + 'gravity_compensation_torques',
122+
SEAJointState,
123+
self._on_sea_joint_state,
124+
queue_size=1,
125+
tcp_nodelay=True)
126+
118127
err_msg = ("%s limb init failed to get current joint_states "
119128
"from %s") % (self.name.capitalize(), joint_state_topic)
120129
baxter_dataflow.wait_for(lambda: len(self._joint_angle.keys()) > 0,
@@ -123,6 +132,10 @@ def __init__(self, limb):
123132
"from %s") % (self.name.capitalize(), ns + 'endpoint_state')
124133
baxter_dataflow.wait_for(lambda: len(self._cartesian_pose.keys()) > 0,
125134
timeout_msg=err_msg)
135+
err_msg = ("%s limb init failed to get current SEA joint state"
136+
"from %s") % (self.name.capitalize(), ns + 'gravity_compensation_torques')
137+
baxter_dataflow.wait_for(lambda: len(self._joint_commanded_angle.keys()) > 0,
138+
timeout_msg=err_msg)
126139

127140
def _on_joint_states(self, msg):
128141
for idx, name in enumerate(msg.name):
@@ -174,6 +187,11 @@ def _on_endpoint_states(self, msg):
174187
),
175188
}
176189

190+
def _on_sea_joint_state(self, msg):
191+
for idx, name in enumerate(msg.name):
192+
if name in self._joint_names[self.name]:
193+
self._joint_commanded_angle[name] = msg.commanded_position[idx]
194+
177195
def joint_names(self):
178196
"""
179197
Return the names of the joints for the specified limb.
@@ -292,6 +310,26 @@ def endpoint_effort(self):
292310
"""
293311
return deepcopy(self._cartesian_effort)
294312

313+
def joint_commanded_angle(self, joint):
314+
"""
315+
Return the requested joint commanded angle.
316+
317+
@type joint: str
318+
@param joint: name of a joint
319+
@rtype: float
320+
@return: commanded angle in radians of individual joint
321+
"""
322+
return self._joint_commanded_angle[joint]
323+
324+
def joint_commanded_angles(self):
325+
"""
326+
Return all joint angles.
327+
328+
@rtype: dict({str:float})
329+
@return: unordered dict of joint name Keys to commanded angle (rad) Values
330+
"""
331+
return deepcopy(self._joint_commanded_angle)
332+
295333
def set_command_timeout(self, timeout):
296334
"""
297335
Set the timeout in seconds for the joint controller

src/joint_trajectory_action/joint_trajectory_action.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,9 @@ def _get_current_error(self, joint_names, set_point):
196196
error = map(operator.sub, set_point, current)
197197
return zip(joint_names, error)
198198

199+
def _get_commanded_position(self, joint_names):
200+
return [self._limb.joint_commanded_angle(joint) for joint in joint_names]
201+
199202
def _update_feedback(self, cmd_point, jnt_names, cur_time):
200203
self._fdbk.header.stamp = rospy.Duration.from_sec(rospy.get_time())
201204
self._fdbk.joint_names = jnt_names
@@ -404,10 +407,10 @@ def _on_trajectory_action(self, goal):
404407

405408
dimensions_dict = self._determine_dimensions(trajectory_points)
406409

407-
if num_points >= 1 and trajectory_points[0].time_from_start.to_sec() > 0:
410+
if trajectory_points[0].time_from_start.to_sec() > 0: # it already retuned when num_points == 0 (see 10 lines above)
408411
# Add current position as trajectory point
409412
first_trajectory_point = JointTrajectoryPoint()
410-
first_trajectory_point.positions = self._get_current_position(joint_names)
413+
first_trajectory_point.positions = self._get_commanded_position(joint_names)
411414
# To preserve desired velocities and accelerations, copy them to the first
412415
# trajectory point if the trajectory is only 1 point.
413416
if dimensions_dict['velocities']:

0 commit comments

Comments
 (0)