diff --git a/dynamixel_controllers/nodes/controller_manager.py b/dynamixel_controllers/nodes/controller_manager.py index 6133ef0..c052a80 100755 --- a/dynamixel_controllers/nodes/controller_manager.py +++ b/dynamixel_controllers/nodes/controller_manager.py @@ -61,6 +61,7 @@ from dynamixel_controllers.srv import StopControllerResponse from dynamixel_controllers.srv import RestartController from dynamixel_controllers.srv import RestartControllerResponse +import importlib class ControllerManager: def __init__(self): @@ -78,7 +79,7 @@ def __init__(self): manager_namespace = rospy.get_param('~namespace') serial_ports = rospy.get_param('~serial_ports') - for port_namespace,port_config in serial_ports.items(): + for port_namespace,port_config in list(serial_ports.items()): port_name = port_config['port_name'] baud_rate = port_config['baud_rate'] readback_echo = port_config['readback_echo'] if 'readback_echo' in port_config else False @@ -132,7 +133,7 @@ def __init__(self): if self.diagnostics_rate > 0: Thread(target=self.diagnostics_processor).start() def on_shutdown(self): - for serial_proxy in self.serial_proxies.values(): + for serial_proxy in list(self.serial_proxies.values()): serial_proxy.disconnect() def diagnostics_processor(self): @@ -143,7 +144,7 @@ def diagnostics_processor(self): diag_msg.status = [] diag_msg.header.stamp = rospy.Time.now() - for controller in self.controllers.values(): + for controller in list(self.controllers.values()): try: joint_state = controller.joint_state temps = joint_state.motor_temps @@ -173,9 +174,9 @@ def check_deps(self): controllers_still_waiting = [] for i,(controller_name,deps,kls) in enumerate(self.waiting_meta_controllers): - if not set(deps).issubset(self.controllers.keys()): + if not set(deps).issubset(list(self.controllers.keys())): controllers_still_waiting.append(self.waiting_meta_controllers[i]) - rospy.logwarn('[%s] not all dependencies started, still waiting for %s...' % (controller_name, str(list(set(deps).difference(self.controllers.keys()))))) + rospy.logwarn('[%s] not all dependencies started, still waiting for %s...' % (controller_name, str(list(set(deps).difference(list(self.controllers.keys())))))) else: dependencies = [self.controllers[dep_name] for dep_name in deps] controller = kls(controller_name, dependencies) @@ -205,7 +206,7 @@ def start_controller(self, req): package_module = __import__(package_path, globals(), locals(), [module_name], -1) else: # reload module if previously imported - package_module = reload(sys.modules[package_path]) + package_module = importlib.reload(sys.modules[package_path]) controller_module = getattr(package_module, module_name) except ImportError as ie: self.start_controller_lock.release() @@ -227,7 +228,7 @@ def start_controller(self, req): if port_name != 'meta' and (port_name not in self.serial_proxies): self.start_controller_lock.release() - return StartControllerResponse(False, 'Specified port [%s] not found, available ports are %s. Unable to start controller %s' % (port_name, str(self.serial_proxies.keys()), controller_name)) + return StartControllerResponse(False, 'Specified port [%s] not found, available ports are %s. Unable to start controller %s' % (port_name, str(list(self.serial_proxies.keys())), controller_name)) controller = kls(self.serial_proxies[port_name].dxl_io, controller_name, port_name) diff --git a/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller.py b/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller.py index bb3a637..c3cdb0d 100755 --- a/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller.py +++ b/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller.py @@ -32,7 +32,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import division + __author__ = 'Antons Rebguns' @@ -166,7 +166,7 @@ def set_acceleration_raw(self, acc): def process_motor_states(self, state_list): if self.running: - state = filter(lambda state: state.id == self.motor_id, state_list.motor_states) + state = [state for state in state_list.motor_states if state.id == self.motor_id] if state: state = state[0] self.joint_state.motor_temps = [state.temperature] diff --git a/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller_dual_motor.py b/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller_dual_motor.py index f58aad9..3b63b35 100644 --- a/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller_dual_motor.py +++ b/dynamixel_controllers/src/dynamixel_controllers/joint_position_controller_dual_motor.py @@ -32,7 +32,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import division + __author__ = 'Antons Rebguns' diff --git a/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller.py b/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller.py index 076bf0f..f1e4777 100644 --- a/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller.py +++ b/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller.py @@ -32,7 +32,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import division + __author__ = 'Antons Rebguns' @@ -151,7 +151,7 @@ def set_torque_limit(self, max_torque): def process_motor_states(self, state_list): if self.running: - state = filter(lambda state: state.id == self.motor_id, state_list.motor_states) + state = [state for state in state_list.motor_states if state.id == self.motor_id] if state: state = state[0] self.joint_state.motor_temps = [state.temperature] diff --git a/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller_dual_motor.py b/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller_dual_motor.py index 018586a..4642bc7 100644 --- a/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller_dual_motor.py +++ b/dynamixel_controllers/src/dynamixel_controllers/joint_torque_controller_dual_motor.py @@ -32,7 +32,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import division + __author__ = 'Antons Rebguns' diff --git a/dynamixel_controllers/src/dynamixel_controllers/joint_trajectory_action_controller.py b/dynamixel_controllers/src/dynamixel_controllers/joint_trajectory_action_controller.py index 4315d36..e3b87e0 100755 --- a/dynamixel_controllers/src/dynamixel_controllers/joint_trajectory_action_controller.py +++ b/dynamixel_controllers/src/dynamixel_controllers/joint_trajectory_action_controller.py @@ -32,7 +32,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import division + __author__ = 'Antons Rebguns' @@ -85,9 +85,9 @@ def __init__(self, controller_namespace, controllers): if c.port_namespace in self.port_to_io: continue self.port_to_io[c.port_namespace] = c.dxl_io - self.joint_states = dict(zip(self.joint_names, [c.joint_state for c in controllers])) + self.joint_states = dict(list(zip(self.joint_names, [c.joint_state for c in controllers]))) self.num_joints = len(self.joint_names) - self.joint_to_idx = dict(zip(self.joint_names, range(self.num_joints))) + self.joint_to_idx = dict(list(zip(self.joint_names, list(range(self.num_joints))))) def initialize(self): ns = self.controller_namespace + '/joint_trajectory_action_node/constraints' @@ -245,7 +245,7 @@ def process_trajectory(self, traj): multi_packet = {} - for port, joints in self.port_to_joints.items(): + for port, joints in list(self.port_to_joints.items()): vals = [] for joint in joints: @@ -276,7 +276,7 @@ def process_trajectory(self, traj): multi_packet[port] = vals - for port, vals in multi_packet.items(): + for port, vals in list(multi_packet.items()): self.port_to_io[port].set_multi_position_and_speed(vals) while time < seg_end_times[seg]: @@ -286,7 +286,7 @@ def process_trajectory(self, traj): msg = 'New trajectory received. Aborting old trajectory.' multi_packet = {} - for port, joints in self.port_to_joints.items(): + for port, joints in list(self.port_to_joints.items()): vals = [] for joint in joints: @@ -299,7 +299,7 @@ def process_trajectory(self, traj): multi_packet[port] = vals - for port, vals in multi_packet.items(): + for port, vals in list(multi_packet.items()): self.port_to_io[port].set_multi_position(vals) self.action_server.set_preempted(text=msg) diff --git a/dynamixel_driver/src/dynamixel_driver/dynamixel_serial_proxy.py b/dynamixel_driver/src/dynamixel_driver/dynamixel_serial_proxy.py index 51dcc87..b859077 100755 --- a/dynamixel_driver/src/dynamixel_driver/dynamixel_serial_proxy.py +++ b/dynamixel_driver/src/dynamixel_driver/dynamixel_serial_proxy.py @@ -197,7 +197,7 @@ def __find_motors(self): rospy.set_param('dynamixel/%s/connected_ids' % self.port_namespace, self.motors) status_str = '%s: Found %d motors - ' % (self.port_namespace, len(self.motors)) - for model_number,count in counts.items(): + for model_number,count in list(counts.items()): if count: model_name = DXL_MODEL_TO_PARAMS[model_number]['name'] status_str += '%d %s [' % (count, model_name)