Project Overview
Specs
Dimensions
Work envelope
Denavit-Hartenberg parameters
Gear ratios
Parts orientation and supports
Bill of Materials (BOM)
Kit versions:
Assembly Instructions
Wiring and Electronics
Open loop:
F800
G90 X 0.00 Y 0.00 Z 0.00 A 0.00 B 0.00 C 0.00

Closed loop
Configuring MKS drivers
Configure each MKS Servo driver to these settings. CAN ID – Axis: 01 – X, 02 – Y, 03 – Z, 04 – A, 05 – B, 06 – C.
Use this tool made by DavidD to mount magnet in the center shaft.
IMPORTANT!
Make sure to tin the power wire tips and secure them firmly in the terminals to prevent short circuit.


Port remap
For MKS57D boards (X and Y axes), remapping is not necessary as they natively support two limit sensors (IN_1 and IN_2). However, you must enable power to the sensors by ensuring that DIP switches 2 and 3 on the MKS57D board are flipped to the “ON” position, which is a common oversight. Once powered, you must also enable limits either through the on-board MKS menu (“EndLimit”) or by sending serial command 90.

In contrast, for MKS42D boards (Z, A, B, and C axes), you must remap the input pins to enable the use of two limit switches (Home and End Limit) by sending the serial command 9E (e.g., hex 03 9E 01 A2 for ID:03) using a Arctos Studio/Settings tab/MKS settings/IO Control. After successful remapping, the “GoHome” function will recognize the sensor input, and you still need to ensure limits are enabled via menu or serial command 90 for the End Limit function to stop the motor in the opposite direction.

Testing the endstops
First put a magnet near each sensor and check that it lights up. Then, WITHOUT A BELT FITTED, send HOME command or select GoHome via MKS menu. Motor should rotate slowly until you trigger the sensor connected to IN1. Then send a command to drive the other direction and manually trigger the other sensor, the motor should stop. When all mounted to arm, before fitting belt, manually move the joint to each limit and adjust the sensor positions in relation to the magnets to ensure they trigger at the right time.

Additional encoders
We are trying to implement double closed loop system with MT6701. Still no off the shelf hall effect sensor that works on CAN bus. But it works with Arduino via PWM mode. The only issue so far was a range limited to 180 degrees.


Datasheets (click on text):
- Nema 23
- Nema 17
- DS3225 servo motor
- A4988 driver
- TMC 2209 driver
- MKS servo 42D/57D drivers
- Arduino Mega 2560 Rev3
- MKS CANable adapter
- CNC Shield V3
- KY003 – endstop
- WSH231 endstop
- MT6701 encoder
Gripper – open loop
Wiring the gripper to Arduino
In order to control the gripper you have to connect the servo DS3225 to the Arduino. It should have 3 wires (red +, black – and white which is signal wire). Since Arduinos output voltage pins are already in use, you can use the voltage pins from CNC shield. They are located in top right corner marked as 5V and GND in yellow and blue colors (pic down there). Signal pin (white wire) should be connected to the pin 6 on Arduino Mega. If you connected the servo this way, you can control it by sending this command for example: M97 B40 T2 This will close the gripper from fully open to fully closed Some value explanation:
- B value has range from 0-499, so to control the angle of the servo from 0 to 360 you should take the proportion into the account. So for each 1* angle B value should be 499/360 = 1.38
T is the time needed to complete the operation in seconds.


Gripper – closed loop
- Download and flash the arduino nano with code from HERE.
- Adjust the voltage on DC-DC converter to 6.5 V
- Connect everything according to diagram

Software setup
Arctos grbl
Flashing GRBL firmware to an Arduino is a process that involves uploading new software to the microcontroller on the board. In order to do this, you’ll need a few things:
- An Arduino MEGA 2560
- A USB cable to connect the board to your computer
- The GRBL firmware (which can be downloaded from this link). It has to be unzipped and zipped the grbl folder only.
- The Arduino IDE software (which can be downloaded from the official Arduino website)
Once you have these things, you can follow the steps below to flash the GRBL firmware to your Arduino:
Step 1: Install the Arduino IDE Software Download the Arduino IDE software and install it on your computer. Once the installation is complete, open the Arduino IDE.
Step 2: Connect the Arduino Board Connect your Arduino board to your computer using the USB cable.
Step 3: Select the Arduino Board Type In the Arduino IDE, go to the “Tools” menu and select “Board.” Choose the type of Arduino board you are using (such as “Arduino Uno” or “Arduino Nano”).
Step 4: Select the Serial Port In the same “Tools” menu, select “Port” and choose the serial port that your Arduino board is connected to. If you’re not sure which port to select, you can check the “Device Manager” on your computer to see which port the Arduino board is using.

Step 5: Open Arduino IDE. Select Sketch > Include Library > Add .zip library. When the window opens, go to the extracted folder, there’ll be another “grbl” folder inside. Select it. Click the File menu. Then go over to Examples > grbl > grbl upload. A new window of Arduino IDE will pop up.
Step 6: Upload the GRBL Firmware
You can upload it to your Arduino board. Click the “Upload” button in the Arduino IDE (it looks like an arrow pointing to the right) to upload the firmware to the board.
Step 8: Verify the Upload After the firmware has been uploaded, you can verify that it was successful by opening the Serial Monitor in the Arduino IDE. Make sure the baud rate is set to 115200, and you should see the GRBL welcome message appear in the monitor window.
Here are the default robot settings you can rewrite in ugs, or pronterface. You can also download it HERE and import it in Machine>Firmware>Import
$0 = 10 (Step pulse time, microseconds)
$1 = 255 (Step idle delay, milliseconds)
$2 = 0 (Step pulse invert, mask)
$3 = 0 (Step direction invert, mask)
$4 = 0 (Invert step enable pin, boolean)
$5 = 0 (Invert limit pins, boolean)
$6 = 0 (Invert probe pin, boolean)
$10 = 0 (Status report options, mask)
$11 = 0.010 (Junction deviation, millimeters)
$12 = 0.002 (Arc tolerance, millimeters)
$13 = 0 (Report in inches, boolean)
$20 = 0 (Soft limits enable, boolean)
$21 = 0 (Hard limits enable, boolean)
$22 = 0 (Homing cycle enable, boolean)
$23 = 0 (Homing direction invert, mask)
$24 = 200.000 (Homing locate feed rate, mm/min)
$25 = 200.000 (Homing search seek rate, mm/min)
$26 = 250 (Homing switch debounce delay, milliseconds)
$27 = 0.000 (Homing switch pull-off distance, millimeters)
$30 = 0 (Maximum spindle speed, RPM)
$31 = 5 (Minimum spindle speed, RPM)
$32 = 0 (Laser-mode enable, boolean)
$100 = 60.000 (X-axis travel resolution, step/mm)
$101 = 576.000 (Y-axis travel resolution, step/mm)
$102 = 576.000 (Z-axis travel resolution, step/mm)
$103 = 200.000
$104 = 122.000
$105 = 122.000
$110 = 1000.000 (X-axis maximum rate, mm/min)
$111 = 1000.000 (Y-axis maximum rate, mm/min)
$112 = 1000.000 (Z-axis maximum rate, mm/min)
$113 = 2000.000
$114 = 2000.000
$115 = 2000.000
$120 = 150.000 (X-axis acceleration, mm/sec^2)
$121 = 150.000 (Y-axis acceleration, mm/sec^2)
$122 = 150.000 (Z-axis acceleration, mm/sec^2)
$123 = 150.000
$124 = 150.000
$125 = 150.000
$130 = 150.000 (X-axis maximum travel, millimeters)
$131 = 200.000 (Y-axis maximum travel, millimeters)
$132 = 150.000 (Z-axis maximum travel, millimeters)
$133 = 800.000
$134 = 800.000
$135 = 800.000
That’s it! You have successfully flashed the GRBL firmware to your Arduino board. You can now use the board to control
ROS
- Make sure you have ROS properly installed with a working workspace. This repository assumes ROS Melodic on Ubuntu 18.04, so make any necessary adjustments if you are using a different configuration. Place the ‘arctos_ros’ package in the ‘src’ directory of your catkin workspace.
- To plan and execute trajectories for the Arctos arm in simulation (using RVIZ with Moveit plugin), run the following terminal
- command
roslaunch arctos_config demo.launch
- Once the window loads, enable “Allow Approximate IK Solutions” in the bottom-left corner. Navigate to the “Planning” tab in the Motion Planning panel of RVIZ. You can set a new goal state by either dragging the interactive marker (the light blue ball at the end effector) or selecting one under “Select Goal State.” After updating the goal state, clicking “Plan and Execute” will generate and execute the trajectory from the start state to the updated goal state.

Controlling the Real Robot, Synchronized with the Simulated Arm’s Trajectories
- Make sure to download the AccelStepper library (AccelStepper Library Download) and the ros_lib library (rosserial-arduino tutorial) in your Arduino development environment.
- If you already have the ros_lib library in your Arduino libraries directory (/libraries), follow the last troubleshooting tip to avoid errors related to “ArmJointState.h”. ROS requires you to remove ros_lib and regenerate it every time you introduce a new custom message.
- Update the pin layout to match your robot and the CNC shield boards in the ‘arctos_moveit_arduino.ino’ file and upload it to your Arduino (assuming you are using a MEGA 2560). Ensure that both the real robot and the simulation start in the same position. To set the simulation upright initially, select “home” from the “Select Goal States” in RVIZ.
- In ‘arctos_moveit_convert.cpp’, replace the
stepsPerRevolution
array with the steps per revolution (or microsteps per revolution) of each of your motors. If you don’t know these values, you can experimentally determine how many microsteps per revolution your motors have using the MultiStepperTest.ino and recording/observing the results. - With the simulation already running, execute the following commands in separate terminal windows:
rosrun rosserial_python serial_node.py /dev/ttyUSB0
(establishes a rosserial node to communicate with the Arduino).rosrun moveo_moveit moveit_convert
(converts joint_state rotations from the simulation to steps and publishes them on the /joint_steps topic, which the Arduino script subscribes to).rostopic pub gripper_angle std_msgs/UInt16 <angle 0-180>
(publishes the gripper angle).
Now, any trajectories planned and executed in the simulation will be echoed on the real Arctos robot.
Directory Structure
arctos_urdf
This directory contains the URDF (Unified Robot Description File) for the Arctos robotic arm. It’s essential for simulating the Arctos arm in RVIZ and configuring it with Moveit.
arctos_moveit_config
Here, you’ll find the configuration files for Moveit, a motion planning framework with a plugin for RVIZ. This configuration is designed for use with the Arctos arm.
arctos_moveit
- arctos_moveit_convert.cpp: This node converts joint_state rotations from the simulation (via the ‘move_group/fake_controller_joint_states’ topic) into steps. It then publishes these steps on the /joint_steps topic. The joint_steps topic is an array of 6 Int16 values (though in the case of the Arctos arm, there are only 5 joints). This array represents the accumulated steps executed by each joint since the arctos_moveit_convert node started running.
- arctos_move_group_interface_coor_1.cpp: This node allows you to hardcode a pose/position for the end effector in the script and plan/execute a trajectory to reach that position. It can also read and output the current pose/position of the end effector.
Troubleshooting
- After following step 7, you should see three new topics created:
- /joint_steps: This topic contains the steps necessary to move each motor to the desired position.
- /joint_steps_feedback: Similar to /joint_steps, but information is published back by the Arduino to verify that it is receiving data correctly.
- /gripper_angle: This topic provides the current angle of the gripper.
- To move the Arctos arm from the command line, use the following command:
rostopic pub joint_steps arctos_moveit/ArmJointState <Joint1 Joint2 Joint3 Joint4 Joint5 0>
- Replace “Joint1, Joint2, etc.” with the number of steps you want each joint to move.
- Use “`rostopic
list“` and search for these topics to check if they are currently running.
- Use
rostopic echo /<topic>
to view the data on <topic> in your terminal. - If you encounter the error message: “error: arctos_moveit/ArmJointState.h: No such file or directory,” perform the following steps in the terminal:
cd <Arduino sketchbook>/libraries rm -rf ros_lib rosrun rosserial_arduino make_libraries.py .
- More information can be found on the ROS wiki:
RoboDK
RoboDK postprocessor for Arctos 0.16.7
This repository contains RoboDK packages for the Arctos robotic arm, enabling motion planning, execution, and simulation in both virtual and real environments.
How to Use:
Requirements
Import Arctos.rdk in RoboDK
- File > Open > Arctos.rdk
- Double click on Prog1 to see the test move
- Import Arctos.py post processor to installation folder. For example “C:\RoboDK\Posts”
- Right click on Prog1 > Select Post Processor > there should be “Arctos” in the list.

Generate robot program
- Right click on Prog1 > Generate robot program > select Arctos > OK
If you want to make your custom program follow the RoboDK tutorials
In short:
- double click on Arctos in design tree below the My Mechanism Base opens the panel
- In panel it is possible to jog and move the robot to desired position More fun way is to click anywhere in space and hit ALT key, it allows to move the robot by pivoting tools on each target.
- Add target to desired position
- Create New program
- Select target
- Add movement to a program (joint, linear, circular)
- Double click on Prog2 to see the movement
- Step 1.
Open robot program in UGS
- Connect the robot with USB cable
- Refresh the Port and select COM port, Select Baud 115200
- Connect the robot
- Make sure it is in the same position as target “Home” in RoboDK
- File > Open > Prog1.gcode
- Toolbox > Reset Zero
- Play the program on robot
Arctos GUI

Open terminal in desktop:
git clone https://github.com/ArctosRobotics/ArctosGUI
Copy scripts interface.py and transform.py to:
/your-path/arctos_ros/src/arctos_moveit/scripts
make sure they are executable with:
sudo chmod +x interface.py
sudo chmod +x transform.py
cd ~/your-path/arctos_ros
catkin build
Now you can go to
cd ~/your-path/arctosgui
Install requirements:
pip3 install -r requirements.txt
Then run
./run.sh
4 tabs will open you can manually open them by:
roslaunch arctos_config demo launch
rosrun moveo_moveit interface.py
rosrun moveo_moveit transform.py
python3 ui.py
Wait for the gui and rviz to show
In moveit rviz go File>Open config or Ctrl+O and open arctosgui_config.rviz
Connect the robot
If you have other port than /dev/ttyACM0 edit files send.py and ros.py to adress your specific port
Plan new toolpath by moving joints or tool Run ROS button will send CAN messages from new pose
Run RoboDK will send gcode.tap file to robot Make sure that you copy the gcode from RoboDK post processor to gcode.tap or adapt it to export code to arctos gui location under the name gcode.tap and replace it.
Set gear ratios in convert.py and roscan.py gear_ratios = [1, 1, 1, 1, 1, 1] # Replace with your actual gearbox ratios
Raw gear ratios. X 13.5 Y 150 Z 150 A 48 B 67.82 C 67.82
In theory raw gear ratios should be multiplied to 0.5, so gear_ratios would be [6.75, 75, 75, 24, 33.91, 33.91] They are not tested!
If your folder is not in desktop and your machine is not named “aa” you should edit those lines in ui.py script according to your path:
BACKGROUND_IMAGE_PATH = "/home/aa/Desktop/arctosgui/img/strelice.png"
BUTTON_IMAGE_PATH = "/home/aa/Desktop/arctosgui/img/bg.png"
ico = Image.open('/home/aa/Desktop/arctosgui/img/icon.png')
Troubleshooting
1. Motors Not Moving
Possible Causes
Each stepper motor has two coils and four wires.
- Identify the coils: Measure resistance between wires — if you feel resistance while turning the shaft, those wires belong to the same coil.
- Correct connection: Connect as A+, A-, B+, B- — one coil on A, the other on B.
- Order does not matter as long as coils are paired correctly.
2. Motor Not Spinning
Electrical Causes
- Check Step/Dir Wiring
- Ensure STEP and DIR pins from the Arduino are correctly connected to the CNC shield.
- Verify that the EN (enable) pin is connected to 5V (or pulled high).
- Stepper Driver Orientation
- Insert the driver in the correct orientation.
- If plugged incorrectly, the driver will be permanently damaged.
- Motor Spinning in the Wrong Direction
- Flip the motor connector 180°, or
- Invert the axis in Arctos Studio → Robot Config.
Software Causes
- Incorrect Steps/mm in GRBL Settings
- If the motor doesn’t move properly, verify and adjust the steps per mm parameter.
- Use Arctos Studio → Settings → Calibrate to fine-tune.
3. Closed-Loop Motor Issues
Common Checks
- CANable Adapter
- If LEDs are flashing while “Direct Mode” is enabled in Arctos Studio, it means CAN messages are being received.
- MKS Driver Configuration
- Double-check your MKS settings and firmware parameters.
- CAN Bus Termination
- Add a 120 Ω resistor at both ends of the CAN line (one near the CANable adapter and one at the last motor).
Caution: If the MKS driver polarity is reversed, it will permanently damage the board.
4. Motion Calibration Issues
If your robot moves more or less than what’s shown in simulation:
- Adjust Steps/mm or Transmission Ratio.
- Go to Arctos Studio → Settings → Calibrate to set the correct motor resolution.
5. CANable Adapter Not Recognized
Possible Fixes
- Use a Higher-Quality USB Cable – Some low-quality cables don’t transfer data properly.
- Install the CANable Driver – Windows 10 usually installs it automatically, but if not, install it manually from the official source.
6. Flashing the GRBL Firmware
To flash GRBL firmware correctly:
- Download the firmware from GitHub.
- Unzip it first.
- Inside, re-zip only the root GRBL folder (not the subfolder).
- Import this new
.zip
file into Arduino IDE → Include Library → Add .ZIP Library.
7. Gearbox Troubleshooting
Cycloidal Gearbox
If the gearbox is not turning or has excessive backlash:
- Ensure the three cycloidal disks and cycloidal shaft are assembled in the correct order and orientation.
- Use a guide pin during assembly to keep disks aligned.
Planetary Gearbox
If the gearbox runs tight or binds:
- A tight gearbox usually means tolerances are off.
- Oversized parts may cause it to jam.
- Undersized parts may cause backlash.
- Try printing at 99% scale to improve fit (optional).
- For best results:
- Pre-run the gearbox using a drill to wear in 3D-printed surfaces.
- Lubricate with vaseline or graphite grease for smoother operation.
8. Motor Overheating
When motors get hot, it means too much current is being drawn.
How to Fix
- Open-Loop Systems
- Adjust torque using the small potentiometer on the driver.
- Always turn the screw only when powered off.
- Closed-Loop Systems
- Adjust the current limit (mA) in the display menu or via Arctos Studio → MKS Settings.
Aim for maximum torque without the motor becoming too hot to touch.
Caution!
Please be avare that this robot can electrocute you. Make sure all wires are secured before turning on. Before building please read the entire manual.
Be aware that runing the stepper motors on high current can get you burned and destroy the robot. Thin undersized wires and bad contacts can induce heat as well. Inverting polarity can damage the boards. Removing the supports with sharp object can get you hurt real bad. 3D printer and soldering iron can burn you like crazy. Robot joints and gearboxes can hurt you.
You can get emotional damage.