Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Resolving Compatibility Issue between python2 and python3 #1

Merged
merged 3 commits into from
Oct 12, 2023
Merged
Changes from all commits
Commits
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
20 changes: 14 additions & 6 deletions src/joint_trajectory_action/joint_trajectory_action.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,14 +28,16 @@
"""
Baxter RSDK Joint Trajectory Action Server
"""
from __future__ import absolute_import

import bisect
from copy import deepcopy
import math
import operator
import numpy as np

import bezier
import minjerk
from . import bezier
from . import minjerk

import rospy

Expand All @@ -58,6 +60,11 @@
import baxter_interface


# Python2's xrange equals Python3's range, and xrange is removed on Python3
if not hasattr(__builtins__, 'xrange'):
xrange = range


class JointTrajectoryActionServer(object):
def __init__(self, limb, reconfig_server, rate=100.0,
mode='position_w_id', interpolation='bezier'):
Expand Down Expand Up @@ -203,10 +210,11 @@ def _update_feedback(self, cmd_point, jnt_names, cur_time):
self._fdbk.desired.time_from_start = rospy.Duration.from_sec(cur_time)
self._fdbk.actual.positions = self._get_current_position(jnt_names)
self._fdbk.actual.time_from_start = rospy.Duration.from_sec(cur_time)
self._fdbk.error.positions = map(operator.sub,
self._fdbk.desired.positions,
self._fdbk.actual.positions
)
self._fdbk.error.positions = list(map(operator.sub,
self._fdbk.desired.positions,
self._fdbk.actual.positions
)
)
self._fdbk.error.time_from_start = rospy.Duration.from_sec(cur_time)
self._server.publish_feedback(self._fdbk)

Expand Down