# roboflex.dynamixel
Support for Robotis' Dynamixel motor product line. Some of it anyway (tested on XH430-V350-R, XH430-W350, XM540-W270, XL-330-M288-T, others may work as well).
We provide two layers to controlling dynamixel motors:
* dynamixel_controller.h defines DynamixelGroupController: a controller for a group of dynamixels connected together (following Robotis' instructions), which uses no message passing or other roboflex functionality at all.
* dynamixel.h, which defines helper classes to control the above, using roboflex.
## DynamixelGroupController (see [dynamixel_controller.h](dynamixel_controller.h))
Controls a group of dynamixel motors, connected together according to Robotis' instructions, to create robot arms, pan-tilt controllers, and other robots. The DynamixelGroupController abstracts the repetitive part of the communication with the motors, and provides a convenient class that can control a group of motors through a callback function: a 'ReadWriteLoop' function. It calls this function synchronously with communication with the dynamixel motors, as fast as the interface can manage, depending on configured baud rate (think > 100hz).
This code is completely stand-alone; it uses nothing from roboflex.
![](roboflex_dynamixel_controller.png)
Each dynamixel can have its own independent operation mode (current, position, velocity, etc), but this class makes it particularly easy to control groups of motors all in the same mode; see the constructors and static methods of DynamixelGroupController in [dynamixel_controller.h](dynamixel_controller.h).
Unless using the PositionController or VelocityController methods to instantiate a controller, the client must decide which control table entries to read and which to write. In general, you can write to the control table entries that are named DXLControlTable::Goal*, and read everything else. Refer to Robotis documentation for details.
## Roboflex additions (see [dynamixel.h](dynamixel.h))
This layer defines additional functionality to integrate with roboflex-style message passing. It defines Messages that encapsulate State and Command types, and several useful nodes.
The first of these is DynamixelGroupControllerNode. This Node sub-class adapts the non-roboflex 'business logic' of DynamixelGroupController to the roboflex paradigm by configuration - you give this Node an instance of a DynamixelGroupController. This Node performs three functions:
1. Adapts DynamixelGroupController's control loop to the roboflex threading model: in `child_thread_fn`, it calls `run_readwrite_loop` on the controller. When `stop` is called on this Node, it stops the thread.
2. Provides a simple, overrideable abstract method to actually perform the control: the user should subclass this class and override:
virtual DXLIdsToValues readwrite_loop_function(
const DynamixelGroupState& state,
const core::MessagePtr last_msg)
{
return DXLIdsToValues{
5: {DXLControlTable::GoalVelocity: 12 },
6: {DXLControlTable::GoalVelocity: 2 }
}
}
# in python:
def readwrite_loop_function(state, last_msg):
# use state and last_msg as you wish
return {
5: {DXLControlTable.GoalVelocity: 12 },
6: {DXLControlTable.GoalVelocity: 2 }
}
# In both of these cases, this means you want to set the goal velocity of
# dynamixel motor with id 5 to 12, and motor 6 to 2.
3. Provides basic message handling. It will:
3.1. Save the most recent message. You can use this to send in, for instance, some new position or velocity you want to move the motors to. This Node's control loop might be operating at a different frequency that the incoming messages - it should still work.
3.2. Broadcast the state and command (your command values) sent to the motor group at every loop cycle, in the form of a `DynamixelCommandStateMessage`.
## Messages
### DynamixelCommandStateMessage:
Encapsulates the a state and command of the dynamixel group. Used to communicate the last-known state of the motors, and last-known command sent to the motors. Serializes this schema to flexbuffers:
{
...
"state": { # the present state of the group of motors:
5: { # motor with id 5
128: 2, # has present velocity = 2
132: 204, # has present position = 204
},
6: { # motor with id 6, etc.
128: 12,
132: 301,
}
}
"command": { # the last-known command you sent
5: {104: 4}, # motor with id 5 should get goal velocity = 4
6: {104: 5} # motor with id 6 should get goal velocity = 5
}
"t0": 170002032.2122312, # time just before communication with motor
"t1": 170002032.2283432, # time just after communication with motor
}
## For more 'distributed' operation:
The second of these is DynamixelGroupNode. This node inherits RunnableNode; it is designed to be started and stopped. When instantiated, this node must be given an instance of a DynamixelGroupController. When started, it runs a ReadWriteLoopFunction on that instance inside its run_readwrite_loop method, using the last known GroupCommandMessage it has received, and then emits a GroupStateMessage.
![](roboflex_dynamixel.png)
We also provided DynamixelRemoteController. This is an abstract base class that requires implementation of the 'readwrite_loop_function' virtual method. Here is where your custom control logic would go. The benefit of this approach is that the DynamixelGroupNode can run in its own thread, and keep up with the motors. This node, then, can be run from anywhere, and using transport classes, the controller can even run on a totally separate computer.
We also provide DynamixelRemoteFrequencyController, which is exactly the same, but is driven at some frequency from a thread via inheritance from FrequencyGenerator.
![](dynamixel_remote_controller.png)
## Troubleshooting
You might benefit from the Robotis Dynamixel Wizard program - just google for it.
If you can't access /dev/ttyUSB0, try this:
sudo usermod -a -G dialout $USER
sudo reboot
Raw data
{
"_id": null,
"home_page": "https://github.com/flexrobotics/roboflex_dynamixel",
"name": "roboflex.dynamixel",
"maintainer": "",
"docs_url": null,
"requires_python": ">=3.6",
"maintainer_email": "",
"keywords": "dynamixel,robotics,middleware,flexbuffers,python,c++,c++20",
"author": "Colin Prepscius",
"author_email": "colinprepscius@gmail.com",
"download_url": "https://files.pythonhosted.org/packages/f7/53/a31a9b0d905750583b51430c96da70d8abe90cfe70c9468227aeb0010d2b/roboflex.dynamixel-0.1.16.tar.gz",
"platform": null,
"description": "# roboflex.dynamixel\n\nSupport for Robotis' Dynamixel motor product line. Some of it anyway (tested on XH430-V350-R, XH430-W350, XM540-W270, XL-330-M288-T, others may work as well).\n\nWe provide two layers to controlling dynamixel motors:\n\n* dynamixel_controller.h defines DynamixelGroupController: a controller for a group of dynamixels connected together (following Robotis' instructions), which uses no message passing or other roboflex functionality at all.\n* dynamixel.h, which defines helper classes to control the above, using roboflex.\n\n\n## DynamixelGroupController (see [dynamixel_controller.h](dynamixel_controller.h))\n\nControls a group of dynamixel motors, connected together according to Robotis' instructions, to create robot arms, pan-tilt controllers, and other robots. The DynamixelGroupController abstracts the repetitive part of the communication with the motors, and provides a convenient class that can control a group of motors through a callback function: a 'ReadWriteLoop' function. It calls this function synchronously with communication with the dynamixel motors, as fast as the interface can manage, depending on configured baud rate (think > 100hz).\n\nThis code is completely stand-alone; it uses nothing from roboflex.\n\n![](roboflex_dynamixel_controller.png)\n\nEach dynamixel can have its own independent operation mode (current, position, velocity, etc), but this class makes it particularly easy to control groups of motors all in the same mode; see the constructors and static methods of DynamixelGroupController in [dynamixel_controller.h](dynamixel_controller.h).\n\nUnless using the PositionController or VelocityController methods to instantiate a controller, the client must decide which control table entries to read and which to write. In general, you can write to the control table entries that are named DXLControlTable::Goal*, and read everything else. Refer to Robotis documentation for details.\n\n\n## Roboflex additions (see [dynamixel.h](dynamixel.h))\n\nThis layer defines additional functionality to integrate with roboflex-style message passing. It defines Messages that encapsulate State and Command types, and several useful nodes.\n\nThe first of these is DynamixelGroupControllerNode. This Node sub-class adapts the non-roboflex 'business logic' of DynamixelGroupController to the roboflex paradigm by configuration - you give this Node an instance of a DynamixelGroupController. This Node performs three functions:\n1. Adapts DynamixelGroupController's control loop to the roboflex threading model: in `child_thread_fn`, it calls `run_readwrite_loop` on the controller. When `stop` is called on this Node, it stops the thread.\n2. Provides a simple, overrideable abstract method to actually perform the control: the user should subclass this class and override:\n\n virtual DXLIdsToValues readwrite_loop_function(\n const DynamixelGroupState& state,\n const core::MessagePtr last_msg) \n {\n return DXLIdsToValues{ \n 5: {DXLControlTable::GoalVelocity: 12 },\n 6: {DXLControlTable::GoalVelocity: 2 }\n }\n }\n\n # in python:\n\n def readwrite_loop_function(state, last_msg):\n # use state and last_msg as you wish\n return {\n 5: {DXLControlTable.GoalVelocity: 12 },\n 6: {DXLControlTable.GoalVelocity: 2 }\n }\n\n # In both of these cases, this means you want to set the goal velocity of\n # dynamixel motor with id 5 to 12, and motor 6 to 2.\n\n3. Provides basic message handling. It will:\n\n 3.1. Save the most recent message. You can use this to send in, for instance, some new position or velocity you want to move the motors to. This Node's control loop might be operating at a different frequency that the incoming messages - it should still work.\n\n 3.2. Broadcast the state and command (your command values) sent to the motor group at every loop cycle, in the form of a `DynamixelCommandStateMessage`.\n\n\n## Messages\n\n### DynamixelCommandStateMessage:\n\nEncapsulates the a state and command of the dynamixel group. Used to communicate the last-known state of the motors, and last-known command sent to the motors. Serializes this schema to flexbuffers:\n\n{\n ...\n \"state\": { # the present state of the group of motors:\n 5: { # motor with id 5\n 128: 2, # has present velocity = 2\n 132: 204, # has present position = 204\n },\n 6: { # motor with id 6, etc.\n 128: 12,\n 132: 301,\n }\n }\n \"command\": { # the last-known command you sent\n 5: {104: 4}, # motor with id 5 should get goal velocity = 4\n 6: {104: 5} # motor with id 6 should get goal velocity = 5\n }\n \"t0\": 170002032.2122312, # time just before communication with motor\n \"t1\": 170002032.2283432, # time just after communication with motor\n}\n\n\n## For more 'distributed' operation:\n\nThe second of these is DynamixelGroupNode. This node inherits RunnableNode; it is designed to be started and stopped. When instantiated, this node must be given an instance of a DynamixelGroupController. When started, it runs a ReadWriteLoopFunction on that instance inside its run_readwrite_loop method, using the last known GroupCommandMessage it has received, and then emits a GroupStateMessage.\n\n![](roboflex_dynamixel.png)\n\nWe also provided DynamixelRemoteController. This is an abstract base class that requires implementation of the 'readwrite_loop_function' virtual method. Here is where your custom control logic would go. The benefit of this approach is that the DynamixelGroupNode can run in its own thread, and keep up with the motors. This node, then, can be run from anywhere, and using transport classes, the controller can even run on a totally separate computer.\n\nWe also provide DynamixelRemoteFrequencyController, which is exactly the same, but is driven at some frequency from a thread via inheritance from FrequencyGenerator.\n\n![](dynamixel_remote_controller.png)\n\n## Troubleshooting\n\nYou might benefit from the Robotis Dynamixel Wizard program - just google for it.\n\nIf you can't access /dev/ttyUSB0, try this:\n\n sudo usermod -a -G dialout $USER\n sudo reboot\n\n\n",
"bugtrack_url": null,
"license": "MIT",
"summary": "Roboflex Dynamixel Library",
"version": "0.1.16",
"project_urls": {
"Homepage": "https://github.com/flexrobotics/roboflex_dynamixel"
},
"split_keywords": [
"dynamixel",
"robotics",
"middleware",
"flexbuffers",
"python",
"c++",
"c++20"
],
"urls": [
{
"comment_text": "",
"digests": {
"blake2b_256": "f753a31a9b0d905750583b51430c96da70d8abe90cfe70c9468227aeb0010d2b",
"md5": "303ab3bceaf46ad0b1910b9c166f1853",
"sha256": "e8d517438eca8de7d63c29e38d853899e2bf43fc65a05dc437bb00ed454a5b8b"
},
"downloads": -1,
"filename": "roboflex.dynamixel-0.1.16.tar.gz",
"has_sig": false,
"md5_digest": "303ab3bceaf46ad0b1910b9c166f1853",
"packagetype": "sdist",
"python_version": "source",
"requires_python": ">=3.6",
"size": 28333,
"upload_time": "2024-01-21T21:19:51",
"upload_time_iso_8601": "2024-01-21T21:19:51.575466Z",
"url": "https://files.pythonhosted.org/packages/f7/53/a31a9b0d905750583b51430c96da70d8abe90cfe70c9468227aeb0010d2b/roboflex.dynamixel-0.1.16.tar.gz",
"yanked": false,
"yanked_reason": null
}
],
"upload_time": "2024-01-21 21:19:51",
"github": true,
"gitlab": false,
"bitbucket": false,
"codeberg": false,
"github_user": "flexrobotics",
"github_project": "roboflex_dynamixel",
"travis_ci": false,
"coveralls": false,
"github_actions": false,
"lcname": "roboflex.dynamixel"
}