Skip to content

Commit 5bb1524

Browse files
Merge pull request #13 from AlbanVl/main
Add the `ChangeBaudrate` method + correct some errors in the README's and update them.
2 parents ca2a40d + e2c28fb commit 5bb1524

5 files changed

Lines changed: 101 additions & 8 deletions

File tree

README.md

Lines changed: 27 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,14 @@ This Python module provides a high-level API to communicate and control ST3215 s
1010
- Write target position, speed, and acceleration
1111
- Rotate continuously in either direction
1212
- Define and correct middle position
13-
- EEPROM locking and ID reconfiguration
13+
- EEPROM locking, ID and baudrate reconfiguration
1414

15+
## Installation
16+
You can install the module using pip:
17+
18+
```bash
19+
pip install -e .
20+
```
1521

1622
## Example Usage
1723

@@ -269,8 +275,8 @@ servo.Rotate(1, 250)
269275
---
270276

271277
### `MoveTo(sts_id, position, speed=2400, acc=50, wait=False)`
272-
Move to a defined position.
273-
Set wait to `True` if you want to wait the end of the move before the function returning
278+
Move to a defined position. Return `None` in case of error.
279+
Set wait to `True` if you want to wait the end of the move before the function returning.
274280

275281
- **Parameters**:
276282
- `sts_id` (int)
@@ -301,7 +307,7 @@ servo.WritePosition(1, 2048)
301307
---
302308

303309
### `ReadPosition(sts_id)`
304-
Read current position. Return `None` in case of error.
310+
Read current position. Return position in case of success, otherwise `None`
305311

306312
- **Parameters**: `sts_id` (int)
307313
- **Returns**: `int` or `None`
@@ -313,7 +319,7 @@ servo.ReadPosition(1)
313319
---
314320

315321
### `ReadSpeed(sts_id)`
316-
Get current speed. Return `None` in case of error.
322+
Get current speed. Return speed in case of success, otherwise `None`
317323

318324
- **Parameters**: `sts_id` (int)
319325
- **Returns**: `(int, int, int)`
@@ -325,7 +331,7 @@ speed, comm, error = servo.ReadSpeed(1)
325331
---
326332

327333
### `LockEprom(sts_id)`
328-
Lock the EEPROM. Return `None` in case of error.
334+
Lock the EEPROM. Return `0` in case of success.
329335

330336
- **Parameters**: `sts_id` (int)
331337
- **Returns**: `int`
@@ -337,7 +343,7 @@ servo.LockEprom(1)
337343
---
338344

339345
### `UnLockEprom(sts_id)`
340-
Unlock the EEPROM. Return `None` in case of error.
346+
Unlock the EEPROM. Return `0` in case of success.
341347

342348
- **Parameters**: `sts_id` (int)
343349
- **Returns**: `int`
@@ -349,7 +355,7 @@ servo.UnLockEprom(1)
349355
---
350356

351357
### `ChangeId(sts_id, new_id)`
352-
Change the servo ID. Return `None` in case of error.
358+
Change the servo ID. Return `None` when sucedeed otherwise the error message
353359

354360
- **Parameters**:
355361
- `sts_id` (int)
@@ -360,6 +366,19 @@ Change the servo ID. Return `None` in case of error.
360366
servo.ChangeId(1, 2)
361367
```
362368

369+
---
370+
### `ChangeBaudrate(sts_id, new_baudrate)`
371+
Change the servo baudrate. Return `None` when sucedeed otherwise the error message
372+
373+
- **Parameters**:
374+
- `sts_id` (int)
375+
- `new_baudrate` (int)
376+
- **Returns**: `None` or `str`
377+
- **Example**:
378+
```python
379+
servo.ChangeBaudrate(1, 4) # 115200
380+
```
381+
363382
---
364383

365384
### `DefineMiddle(sts_id)`

st3215/st3215.py

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -564,5 +564,29 @@ def ChangeId(self, sts_id, new_id):
564564
else:
565565
return "new_id is not between 0 and 253"
566566

567+
def ChangeBaudrate(self, sts_id, new_baudrate):
568+
"""
569+
Change Baudrate of a Servo.
570+
571+
:param sts_id: Actual ID for the servo
572+
:param new_baudrate: New baudrate for the servo (in bps)
573+
574+
:return: None when sucedeed otherwise the error message
575+
"""
576+
if isinstance(new_baudrate, int) and 0 <= new_baudrate <= 7:
577+
578+
if not self.PingServo(sts_id):
579+
return f"Could not find servo: {sts_id}"
567580

581+
if self.UnLockEprom(sts_id) != COMM_SUCCESS:
582+
return "Could not unlock Eprom"
583+
584+
if self.write1ByteTxOnly(sts_id, STS_BAUD_RATE, new_baudrate) != COMM_SUCCESS:
585+
return "Could not change Servo Baudrate"
586+
587+
self.LockEprom(sts_id)
588+
return None
589+
else:
590+
return "baudrate is not valid"
591+
568592

test/README.md

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,16 @@ Comprehensive test of servo control functions.
9292
- **Purpose**: Test StartServo, SetAcceleration, SetSpeed, rotation mode, position mode, and StopServo
9393
- **⚠️ Important**: Ensure servo has enough physical clearance for movement
9494

95+
### Test 11: Change baudrate
96+
Tests baud rate changing functionality.
97+
- **File**: `test_11_change_baudrate.py`
98+
- **Purpose**: Change servo communication baud rate and verify
99+
100+
### Test 12: Read Position
101+
Tests position reading functionality.
102+
- **File**: `test_12_read_position.py`
103+
- **Purpose**: Read current servo position
104+
95105
## Safety Notes
96106

97107
- Ensure proper power supply is connected before running tests

test/test_11_change_baudrate.py

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
from st3215 import ST3215
2+
3+
baudrate = [1000000, 500000, 250000, 128000, 115200, 76800, 57600, 38400]
4+
baudrate_nb = 2
5+
prev_baud_nb = 0
6+
7+
servo = ST3215('COM7')
8+
print("Default baudrate:", servo.portHandler.baudrate)
9+
print("Close port...")
10+
servo.portHandler.closePort()
11+
print("Reopen port with previous baudrate:", baudrate[prev_baud_nb])
12+
servo.portHandler.baudrate = baudrate[prev_baud_nb]
13+
servo.portHandler.openPort()
14+
print("PingServo:", servo.PingServo(1))
15+
status = servo.ChangeBaudrate(1, baudrate_nb)
16+
if status != None:
17+
print("Baudrate change failed with status:", status)
18+
else:
19+
print("Baudrate change successful")
20+
print("Close port...")
21+
servo.portHandler.closePort()
22+
print("Reopen port with new baudrate:", baudrate[baudrate_nb])
23+
servo.portHandler.baudrate = baudrate[baudrate_nb]
24+
print("Current baudrate:", servo.portHandler.baudrate)
25+
servo.portHandler.openPort()
26+
print("PingServo:", servo.PingServo(1))

test/test_12_read_position.py

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
from st3215 import ST3215
2+
3+
baudrate = [1000000, 500000, 250000, 128000, 115200, 76800, 57600, 38400]
4+
baudrate_nb = 0
5+
prev_baud_nb = 0
6+
7+
servo = ST3215('COM7')
8+
print("Default baudrate:", servo.portHandler.baudrate)
9+
print("Close port...")
10+
servo.portHandler.closePort()
11+
print("Reopen port with the right baudrate:", baudrate[baudrate_nb])
12+
servo.portHandler.baudrate = baudrate[baudrate_nb]
13+
servo.portHandler.openPort()
14+
print("Position:", servo.ReadPosition(1))

0 commit comments

Comments
 (0)