MX-12W - is it possible to read present position while in Wheel Mode?

I am working on a project that uses an MX-12W servo to turn a payload in a direction provided by a sensor array tracking an object of interest. Currently the servo is set to Joint Mode, which means that sometimes the servo has to turn the long way around to follow the tracked object.

For example, if the tracked object starts in front of the system (orientation 0°, position 2048), and goes around counter-clockwise until it’s behind it (orientation 180°, position 4095), then keeps moving in the same direction, the servo cannot keep turning counter-clockwise, but instead has to turn around clockwise all the way back (orientation -180°, position 0) in order to keep following the object.

I could set the servo to Multi-turn Mode, but that would just attenuate, not solve the problem: if the tracked object kept going around the system in the same direction, eventually the servo would become unable to turn, and would be forced to “rewind” in order to recover its freedom of movement.

I thought that a better solution would be to set the servo to Wheel Mode, and when given a target position, set a speed in the appropriate direction, then monitor the present position to stop the servo when it reached its destination. However it’s not clear from the documentation whether it’s possible to read present position while in Wheel Mode — the documentation for the AX-12’s explicitly states that it’s not, but for the MX-12W it’s not confirmed one way or another.

Is it possible to read the present position of an MX-12W servo moving in Wheel Mode? If not, how else could I avoid having to “rewind” the servo while targeting specific axis positions?

For the AX-12, the Present Position (PP) sensor is only capable of a range from 0 to 300 degrees so there is an “unknown” zone of 60 degrees remaining. However the PP sensor on your MX-12W is capable of the full range of 0 to 360 degrees, so you should be able to check on the PP any time that you want to. But I do not have an MX-12W handy to verify this issue for you with certainty!:pensive:

BTW your control idea via wheel mode should work. A long time ago I had a similar project with AX-12A - see this video

For the record, it is possible to switch the MX-12W to Wheel Mode, set a moving speed and read the present position as the servo turns around. See the below Python code for reference:

from dynamixel_sdk import *

DEVICENAME = '/dev/ttyUSB0'
BAUDRATE = 1000000
PROTOCOL_VERSION = 1.0
DXL_ID = 11
ADDR_TORQUE_ENABLE = 24
ADDR_PRESENT_POSITION = 36
ADDR_CW_ANGLE_LIMIT = 6
ADDR_CCW_ANGLE_LIMIT = 8
ADDR_MOVING_SPEED = 32

port = PortHandler(DEVICENAME)
port.openPort()
port.setBaudRate(BAUDRATE)

servo = PacketHandler(PROTOCOL_VERSION)

def write(writer, address, value):
    (result, error_code) = writer(port, DXL_ID, address, value)
    if result != COMM_SUCCESS:
        error_message = servo.getRxPacketError(error_code)
        print(f'Error writing value ({value}) to address {address}: "{error_message}"')

def write1Byte(address, value):
    write(servo.write1ByteTxRx, address, value)

def write2Byte(address, value):
    write(servo.write2ByteTxRx, address, value)

# Enable torque and set servo in Wheel Mode.
write1Byte(ADDR_TORQUE_ENABLE, 1)
write2Byte(ADDR_CW_ANGLE_LIMIT, 0)
write2Byte(ADDR_CCW_ANGLE_LIMIT, 0)

# Set a moving speed of approximately 10 RPM counter-clockwise.
write2Byte(ADDR_MOVING_SPEED, 10)

# Read servo position.
try:
    while True:
        (position, result, error_code) = servo.read2ByteTxRx(port, DXL_ID, ADDR_PRESENT_POSITION)
        if result != COMM_SUCCESS:
            error_message = servo.getRxPacketError(error_code)
            print(f'Error reading servo position: "{error_message}"')
            break

        print(position)
except KeyboardInterrupt:
    pass

port.closePort()

Position values are between 0 and 4095, wrapping around as the servo completes a full turn.

1 Like

This topic was automatically closed 3 days after the last reply. New replies are no longer allowed.