How do you disable missing servos?

Hello. I am just starting out with building my Poppy robot, and since I can’t afford to buy all the parts right away, I am starting off with just the two cheaper hear servos. However, when I try to connect to the robot, I get errors telling me other motors can’t be found, and the robot can’t be started:

Attempt 1 to start the robot…
Could not find the motors (32, 33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54, 31) on bus /dev/ttyACM0.
Attempt 2 to start the robot…
Another instance of pypot use the port /dev/ttyACM0. You should restart your Python kernel to pass through this issue.
Attempt 3 to start the robot…
Could not find the motors (32, 33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54, 31) on bus /dev/ttyACM0.
Attempt 4 to start the robot…
Another instance of pypot use the port /dev/ttyACM0. You should restart your Python kernel to pass through this issue.
Attempt 5 to start the robot…
Could not find the motors (32, 33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54, 31) on bus /dev/ttyACM0.
Could not start up the robot…
Traceback (most recent call last):
File “/home/poppy/miniconda/bin/poppy-services”, line 6, in
sys.exit(main())
File “/home/poppy/miniconda/lib/python2.7/site-packages/poppy/creatures/services_launcher.py”, line 179, in main
with closing(start_poppy_with_services(args)):
File “/home/poppy/miniconda/lib/python2.7/site-packages/poppy/creatures/services_launcher.py”, line 38, in start_poppy_with_services
raise exc_inst
pypot.dynamixel.io.abstract_io.DxlError: Could not find the motors (32, 33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54, 31) on bus /dev/ttyACM0.

Is it possible to disable some of the motors so the poppy-humanoid software doesn’t search for them? I tried removing the motors from poppy_humanoid.json config file, but I’m still getting errors.

I am running this on a Raspberry Pi 3, connecting motors with USB2AX

You can set the motors as broken in the config file:

"l_elbow_y": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 44,
      "angle_limit": [
        -148,
        1
      ],
      "orientation": "direct",
      "broken": true
    }

This should do the trick. Pypot will still create the Python object but will not try to synchronise them will “real motors”.

Seems easy enough, but still running into problems.
I edited ~/dev/poppy_humanoid/configuration/poppy_humanoid.json marking all missing motors as directed, but when I try to run
poppy = PoppyHumanoid()
from python, I get

WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[36, 37]
WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[]

with the command freezing.

If I change the json ports from “auto” to “/dev/ttyACM0” it gives me

WARNING:pypot.robot.config:Could not find the motors (32, 33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54, 31) on bus /dev/ttyACM0.
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=31, address=6, length=4) to motors 31
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=32, address=6, length=4) to motors 32
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=33, address=6, length=4) to motors 33
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=34, address=6, length=4) to motors 34
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=35, address=6, length=4) to motors 35
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=41, address=6, length=4) to motors 41
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=42, address=6, length=4) to motors 42
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=43, address=6, length=4) to motors 43
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=44, address=6, length=4) to motors 44
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=51, address=6, length=4) to motors 51
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=52, address=6, length=4) to motors 52
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=53, address=6, length=4) to motors 53
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=54, address=6, length=4) to motors 54
---------------------------------------------------------------------------
DxlError                                  Traceback (most recent call last)
<ipython-input-1-9baaa5bd1201> in <module>()
      1 from poppy.creatures import PoppyHumanoid
      2 
----> 3 robot = PoppyHumanoid(use_http=True, start_services=True)

/home/poppy/miniconda/lib/python2.7/site-packages/poppy/creatures/abstractcreature.pyc in __new__(cls, base_path, config, simulator, scene, host, port, id, use_snap, snap_host, snap_port, snap_quiet, use_http, http_host, http_port, http_quiet, use_remote, remote_host, remote_port, start_background_services, sync, **extra)
    117         else:
    118             try:
--> 119                 poppy_creature = from_json(config, sync, **extra)
    120             except IndexError as e:
    121                 raise IOError('Connection to the robot failed! {}'.format(e.message))

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in from_json(json_file, sync, strict, use_dummy_io, **extra)
    270         config = json.load(f, object_pairs_hook=OrderedDict)
    271 
--> 272     return from_config(config, sync=sync, strict=strict, use_dummy_io=use_dummy_io, **extra)
    273 
    274 

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in from_config(config, strict, sync, use_dummy_io, **extra)
     60         attached_ids = [m.id for m in attached_motors]
     61         if not use_dummy_io:
---> 62             dxl_io = dxl_io_from_confignode(config, c_params, attached_ids, strict)
     63 
     64             check_motor_eprom_configuration(config, dxl_io, motor_names)

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in dxl_io_from_confignode(config, c_params, ids, strict)
    172     dxl_io = DxlIOCls(port=port,
    173                       use_sync_read=sync_read,
--> 174                       error_handler_cls=handler)
    175 
    176     found_ids = dxl_io.scan(ids)

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in __init__(self, port, baudrate, timeout, use_sync_read, error_handler_cls, convert)
     73         self._serial_lock = threading.Lock()
     74 
---> 75         self.open(port, baudrate, timeout)
     76 
     77     def __enter__(self):

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in open(self, port, baudrate, timeout)
     96 
     97             """
---> 98         self._open(port, baudrate, timeout)
     99         logger.info("Opening port '%s'", self.port,
    100                     extra={'port': port,

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in _open(self, port, baudrate, timeout, max_recursion)
    118 
    119                 if port in self.__used_ports:
--> 120                     raise DxlError('Another instance of pypot use the port {}. You should restart your Python kernel to pass through this issue.'.format(port))
    121 
    122                 # Dirty walkaround to fix a strange bug.

as if it’s completely ignoring the broken tags.

Here’s an example of what json looks like

  "motors": {
    "l_elbow_y": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 44,
      "angle_limit": [
        -148,
        1
      ],
      "orientation": "direct",
      "broken": true
    },

For now I basically dug through PyPot documentation and did this:

import pypot.robot.

my_config = {
    'controllers': {
        'head_controler': {
            'port': '/dev/ttyACM0',
            'sync_read': True,
            'attached_motors': ['head'],
            'protocol': 1,
        }
    },
    'motorgroups': {
        'head': ['head_z', 'head_y']
    },
    'motors': {
        'head_y': {
            'id': 37,
            'type': 'AX-12',
            'orientation': 'indirect',
            'offset': 0.0,
            'angle_limit': (-90.0, 90.0),
        },
        'head_z': {
            'id': 36,
            'type': 'AX-12',
            'orientation': 'direct',
            'offset': 0.0,
            'angle_limit': (-90.0, 90.0),
        }
    }
}

poppy = pypot.robot.from_config(my_config)

which gives me control over just the motors I need, and I guess I can keep adding more servos as I get them until I have the whole thing, but I feel I may be missing out on some of the PoppyHumanoid() features.

I guess the issue comes from the fact that in your case there is an entire “broken” bus. Can you try with the torso configuration?

It basically the same as the humanoid but with only the upper bus.

Finally had time to get back to this. Unfortunately still doesn’t work. All motors but head_z and head_y have been disabled, but running

poppy = PoppyTorso()

results in

WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[44]
WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[]

and freezes. If I interrupt the kernel, I get the full error message:

---------------------------------------------------------------------------
KeyboardInterrupt                         Traceback (most recent call last)
<ipython-input-2-45ad582bf5ae> in <module>()
----> 1 poppy = PoppyTorso()

/home/poppy/miniconda/lib/python2.7/site-packages/poppy/creatures/abstractcreature.pyc in __new__(cls, base_path, config, simulator, scene, host, port, id, use_snap, snap_host, snap_port, snap_quiet, use_http, http_host, http_port, http_quiet, use_remote, remote_host, remote_port, start_background_services, sync, **extra)
    117         else:
    118             try:
--> 119                 poppy_creature = from_json(config, sync, **extra)
    120             except IndexError as e:
    121                 raise IOError('Connection to the robot failed! {}'.format(e.message))

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in from_json(json_file, sync, strict, use_dummy_io, **extra)
    270         config = json.load(f, object_pairs_hook=OrderedDict)
    271 
--> 272     return from_config(config, sync=sync, strict=strict, use_dummy_io=use_dummy_io, **extra)
    273 
    274 

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in from_config(config, strict, sync, use_dummy_io, **extra)
     60         attached_ids = [m.id for m in attached_motors]
     61         if not use_dummy_io:
---> 62             dxl_io = dxl_io_from_confignode(config, c_params, attached_ids, strict)
     63 
     64             check_motor_eprom_configuration(config, dxl_io, motor_names)

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/config.pyc in dxl_io_from_confignode(config, c_params, ids, strict)
    151 
    152     if port == 'auto':
--> 153         port = pypot.dynamixel.find_port(ids, strict)
    154         logger.info('Found port {} for ids {}'.format(port, ids))
    155 

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/__init__.pyc in find_port(ids, strict)
     86             try:
     87                 with DxlIOCls(port) as dxl:
---> 88                     _ids_founds = dxl.scan(ids)
     89                     ids_founds += _ids_founds
     90 

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in scan(self, ids)
    218     def scan(self, ids=range(254)):
    219         """ Pings all ids within the specified list, by default it finds all the motors connected to the bus. """
--> 220         return [id for id in ids if self.ping(id)]
    221 
    222     # MARK: - Specific Getter / Setter

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in ping(self, id)
    211 
    212         try:
--> 213             self._send_packet(pp, error_handler=None)
    214             return True
    215         except DxlTimeoutError:

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in _send_packet(self, instruction_packet, wait_for_status_packet, error_handler, _force_lock)
    524 
    525         if not error_handler:
--> 526             return self.__real_send(instruction_packet, wait_for_status_packet, _force_lock)
    527 
    528         try:

/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/io/abstract_io.pyc in __real_send(self, instruction_packet, wait_for_status_packet, _force_lock)
    483 
    484             data = instruction_packet.to_string()
--> 485             nbytes = self._serial.write(data)
    486             if len(data) != nbytes:
    487                 raise DxlCommunicationError(self,

/home/poppy/miniconda/lib/python2.7/site-packages/serial/serialposix.pyc in write(self, data)
    523                     assert timeout is None
    524                     # wait for write operation
--> 525                     abort, ready, _ = select.select([self.pipe_abort_write_r], [self.fd], [], None)
    526                     if abort:
    527                         os.read(self.pipe_abort_write_r, 1)

KeyboardInterrupt: 

If I change the port from Auto to /dev/ttyACM0, I get this instead

WARNING:pypot.robot.config:Could not find the motors (33, 34, 35, 41, 42, 43, 44, 51, 52, 53, 54) on bus /dev/ttyACM0.
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=33, address=6, length=4) to motors 33
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=34, address=6, length=4) to motors 34
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=35, address=6, length=4) to motors 35
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=41, address=6, length=4) to motors 41
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=42, address=6, length=4) to motors 42
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=43, address=6, length=4) to motors 43
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=44, address=6, length=4) to motors 44
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=51, address=6, length=4) to motors 51
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=52, address=6, length=4) to motors 52
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=53, address=6, length=4) to motors 53
WARNING:pypot.dynamixel.error:Timeout after sending DxlReadDataPacket(id=54, address=6, length=4) to motors 54
Exception in thread Thread-4:
Traceback (most recent call last):
  File "/home/poppy/miniconda/lib/python2.7/threading.py", line 810, in __bootstrap_inner
    self.run()
  File "/home/poppy/miniconda/lib/python2.7/threading.py", line 763, in run
    self.__target(*self.__args, **self.__kwargs)
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/utils/stoppablethread.py", line 121, in _wrapped_target
    self._setup()
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/controller.py", line 52, in setup
    self.regname))
IOError: Cannot initialize syncloop for "pid_gain". You need to desactivate sync_read if you use a usb2dynamixel device. 

Exception in thread Thread-3:
Traceback (most recent call last):
  File "/home/poppy/miniconda/lib/python2.7/threading.py", line 810, in __bootstrap_inner
    self.run()
  File "/home/poppy/miniconda/lib/python2.7/threading.py", line 763, in run
    self.__target(*self.__args, **self.__kwargs)
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/utils/stoppablethread.py", line 121, in _wrapped_target
    self._setup()
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/dynamixel/syncloop.py", line 22, in setup
    [c.start() for c in self.controllers]
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/robot/controller.py", line 25, in start
    self.wait_to_start()
  File "/home/poppy/miniconda/lib/python2.7/site-packages/pypot/utils/stoppablethread.py", line 86, in wait_to_start
    'for details.'.format(self._thread.name))
RuntimeError: Setup failed, see Thread-4 Tracebackfor details.

Basically it’s as if it is completely ignoring the “broken”: true statements in the poppy_torso.json config file

I just tried on my side and it seems to work as expected. Can you post the json file you are using?

Another possible problem, in this log it seems that it only find one motor with id 44 not two:

WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[44]
WARNING:pypot.dynamixel:Port:/dev/ttyACM0 ids found:[]

It’s this, located in /miniconda/lib/python2.7/site-packages/poppy_torso/configuration

{
  "controllers": {
    "upper_body_controller": {
      "sync_read": false,
      "attached_motors": [
        "torso",
        "head",
        "arms"
      ],
      "port": "auto"
    }
  },
  "motorgroups": {
    "head": [
      "head_z",
      "head_y"
    ],
    "r_arm": [
      "r_shoulder_y",
      "r_shoulder_x",
      "r_arm_z",
      "r_elbow_y"
    ],
    "torso": [
      "abs_z",
      "bust_y",
      "bust_x"
    ],
    "l_arm": [
      "l_shoulder_y",
      "l_shoulder_x",
      "l_arm_z",
      "l_elbow_y"
    ],
    "arms": [
      "l_arm",
      "r_arm"
    ]
  },
  "motors": {
    "l_elbow_y": {
      "offset": -90.0,
      "type": "MX-28",
      "id": 44,
      "angle_limit": [
        -140,
        0
      ],
      "orientation": "direct",
      "broken": true
    },
    "head_y": {
      "offset": 20.0,
      "type": "AX-12",
      "id": 37,
      "angle_limit": [
        -40,
        8
      ],
      "orientation": "indirect"
    },
    "r_arm_z": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 53,
      "angle_limit": [
        -90,
        90
      ],
      "orientation": "indirect",
      "broken": true
    },
    "head_z": {
      "offset": 0.0,
      "type": "AX-12",
      "id": 36,
      "angle_limit": [
        -100,
        100
      ],
      "orientation": "direct"
    },
    "r_shoulder_x": {
      "offset": 90.0,
      "type": "MX-28",
      "id": 52,
      "angle_limit": [
        -110,
        105
      ],
      "orientation": "indirect",
      "broken": true
    },
    "r_shoulder_y": {
      "offset": 90,
      "type": "MX-28",
      "id": 51,
      "angle_limit": [
        -155,
        120
      ],
      "orientation": "indirect",
      "broken": true
    },
    "r_elbow_y": {
      "offset": -90.0,
      "type": "MX-28",
      "id": 54,
      "angle_limit": [
        0,
        147
      ],
      "orientation": "indirect",
      "broken": true
    },
    "l_arm_z": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 43,
      "angle_limit": [
        -90,
        90
      ],
      "orientation": "indirect",
      "broken": true
    },
    "abs_z": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 33,
      "angle_limit": [
        -80,
        80
      ],
      "orientation": "direct",
      "broken": true
    },
    "bust_y": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 34,
      "angle_limit": [
        -46,
        23
      ],
      "orientation": "indirect",
      "broken": true
    },
    "bust_x": {
      "offset": 0.0,
      "type": "MX-28",
      "id": 35,
      "angle_limit": [
        -40,
        40
      ],
      "orientation": "indirect",
      "broken": true
    },
    "l_shoulder_x": {
      "offset": -90.0,
      "type": "MX-28",
      "id": 42,
      "angle_limit": [
        -105,
        110
      ],
      "orientation": "indirect",
      "broken": true
    },
    "l_shoulder_y": {
      "offset": 90,
      "type": "MX-28",
      "id": 41,
      "angle_limit": [
        -120,
        155
      ],
      "orientation": "direct",
      "broken": true
    }
  }
}

I’m wondering if this may be something with Raspberry Pi or networking/serial stuff…