Wiki source code of LSS - Communication Protocol

Version 159.1 by RB1 on 2020/03/11 09:48

Show last authors
1 (% class="wikigeneratedid" id="HTableofContents" %)
2 **Page Contents**
3
4 {{toc depth="3"/}}
5
6 = Serial Protocol =
7
8 The custom Lynxmotion Smart Servo (LSS) serial protocol was created in order to be as simple and straightforward as possible from a user perspective ("human readable format"), while at the same time compact and robust yet highly versatile. The protocol was based on Lynxmotion's SSC-32 RC servo controller and almost everything one might expect to be able to configure for a smart servo motor is available.
9
10 In order to have servos react differently when commands are sent to all servos in a serial bus, the first step a user should take is to assign a different ID number to each servo (explained below). Once this has been done, only the servo(s) which have been assigned to the ID sent as part of the command will follow that command. There is currently no CRC / checksum implemented as part of the protocol.
11
12 == Session ==
13
14 A "session" is defined as the time between when the servo is powered ON to when it is powered OFF or reset.
15
16 Note #1: For a given session, the action related to a specific commands overrides the stored value in EEPROM.
17 Note #2: During the power-on / reset process the LSS cannot accept commands for a small amount of time (1.25 s).
18 You can ensure the LSS is ready by using a query command to check for response (ex: #[id]Q\r or #[id]QID\r). If the LSS is ready for commands (initialized) it will respond to the query. A timeout between 50-100 ms is recommended.
19
20 == Action Commands ==
21
22 Action commands tell the servo, within that session, to do something (i.e. "take an action"). The types of action commands which can be sent are described below, and they cannot be combined with other commands such as queries or configurations. Only one action command can be sent at a time. Action commands are session-specific, therefore once a servo is power cycled, it will not have any "memory" of previous actions or virtual positions (described below on this page). Action commands are sent serially to the servo's Rx pin and must be sent in the following format:
23
24 1. Start with a number sign # (U+0023)
25 1. Servo ID number as an integer
26 1. Action command (one to three letters, no spaces, capital or lower case)
27 1. Action value in the correct units with no decimal
28 1. End with a control / carriage return '<cr>'
29
30 (((
31 Ex: #5PD1443<cr>
32
33 This sends a serial command to all servo's Rx pins which are connected to the bus and only servo(s) with ID #5 will move to a position in tenths of degrees ("PD") of 144.3 degrees. Any servo on the bus which does not have ID 5 will take no action when receiving this command.
34
35 == Action Modifiers ==
36
37 Only two commands can be used as action modifiers: Timed Move (T) and Speed (S) described below. Action modifiers can only be used with certain action commands. The format to include a modifier is:
38
39 1. Start with a number sign # (U+0023)
40 1. Servo ID number as an integer
41 1. Action command (one to three letters, no spaces, capital or lower case)
42 1. Action value in the correct units with no decimal
43 1. Modifier command (one letter)
44 1. Modifier value in the correct units with no decimal
45 1. End with a control / carriage return '<cr>'
46
47 Ex: #5P1456T1263<cr>
48
49 This results in the servo with ID #5 rotating from the current angular position to a pulse position ("P") of 1456 in a time ("T") of 1263 milliseconds.
50 )))
51
52 == Query Commands ==
53
54 Query commands request information from the servo. They are received via the Rx pin of the servo, and the servo's reply is sent via the servo's Tx pin. Using separate lines for Tx and Rx is called "full duplex". Query commands are also similar to action and configuration commands and must use the following format:
55
56 1. Start with a number sign # (U+0023)
57 1. Servo ID number as an integer
58 1. Query command (one to three letters, no spaces, capital or lower case)
59 1. End with a control / carriage return '<cr>'
60
61 (((
62 Ex: #5QD<cr>Query position in degrees for servo #5
63 )))
64
65 (((
66 The query will return a serial string (almost instantaneously) via the servo's Tx pin with the following format:
67
68 1. Start with an asterisk * (U+002A)
69 1. Servo ID number as an integer
70 1. Query command (one to three letters, no spaces, capital letters)
71 1. The reported value in the units described, no decimals.
72 1. End with a control / carriage return '<cr>'
73
74 There is currently no option to control how fast a servo replies after it has received a query command, therefore when sending a query command to the bus, the controller should be prepared to immediately "listen" for and parse the reply. Sending multiple queries on a bus in fast succession may result in replies overlapping and giving incorrect or corrupt data. As such, the controller should receive a reply before sending a new command. A reply to the query sent above might be:
75
76 (((
77 Ex: *5QD1443<cr>
78 )))
79
80 This indicates that servo #5 is currently at 144.3 degrees (1443 tenths of degrees).
81
82 == Configuration Commands ==
83
84 Configuration commands and corresponding values affect a servo's defaults which are written to and read from the servo's EEPROM. These configurations are retained in memory after the servo is reset or power is cut / lost. Some configuration commands affect the session, while others do not. In the Command table below, the column "Session" denotes if the configuration command affects the session.. Not all action commands have a corresponding configuration command and vice versa. More information about which configuration commands are retained when in RC mode can be found on the [[LSS - RC PWM page>>doc:lynxmotion-smart-servo.lss-radio-control-pwm.WebHome]]. Configuration commands are not cumulative, in that if two configurations are sent, one after the next, only the last configuration is used and stored. The format to send a configuration command is identical to that of an action command:
85
86 1. Start with a number sign # (U+0023)
87 1. Servo ID number as an integer
88 1. Configuration command (two to three letters, no spaces, capital or lower case)
89 1. Configuration value in the correct units with no decimal
90 1. End with a control / carriage return '<cr>'
91
92 Ex: #5CO-50<cr>
93
94 This configures an absolute origin offset ("CO") with respect to factory origin to servo with ID #5 and changes the offset for that session to -5.0 degrees (50 tenths of degrees). Once the servo is powered off and then powered on, zeroing the servo will cause it to move to -5.0 degrees with respect to the factory origin and report its position as 0 degrees. Configuration commands can be undone / reset either by sending the servo's default value for that configuration, or by doing a factory reset (clears all configurations) described below.
95
96 **Session vs Configuration Query**
97
98 By default, the query command returns the sessions' value. Should no action commands have been sent to change the session value, it will return the value saved in EEPROM which will either be the servo's default, or modified with a configuration command. In order to query the value stored in EEPROM (configuration), add a '1' to the query command:
99
100 Ex: #5CSR20<cr> immediately sets the maximum speed for servo #5 to 20rpm (explained below) and changes the value in memory.
101
102 After RESET, a command of #5SR4<cr> sets the session's speed to 4rpm, but does not change the configuration value in memory. Therefore:
103
104 #5QSR<cr> would return *5QSR4<cr> which represents the value for that session, whereas
105
106 #5QSR1<cr> would return *5QSR20<cr> which represents the value in EEPROM
107
108 == Virtual Angular Position ==
109
110 The ability to store a "virtual angular position" is a feature which allows for rotation beyond 360 degrees, permitting multiple rotations of the output horn, moving the center position and more. In virtual position mode, the "absolute position" would be the angle of the output shaft with respect to a 360.0 degree circle, and can be obtained by taking the modulus (with respect to 360 degrees) of the value. For example if the virtual position is reported as 15335 (or 1533.5 degrees), taking the modulus would give 93.5 degrees (3600 * 4 + 935 = 15335) as the absolute position (assuming no origin offset).
111
112 [[image:LSS-servo-positions.jpg]]
113
114 In this example, the gyre direction (explained below, a.k.a. "rotation direction") is positive (clockwise), and origin offset has not been modified. Each square represents 30 degrees. The following command is sent:
115
116 #1D-300<cr> This causes the servo to move to -30.0 degrees (green arrow)
117
118 #1D2100<cr> This second position command is sent to the servo, which moves it to 210.0 degrees (orange arrow)
119
120 #1D-4200<cr> This next command rotates the servo counterclockwise to a position of -420 degrees (red arrow), which means one full rotation of 360 degrees plus 60.0 degrees (420.0 - 360.0), with a virtual position of -420.0 degrees.
121
122 Although the final physical position would be the same as if the servo were commanded to move to -60.0 degrees, the servo is in fact at -420.0 degrees.
123
124 #1D4800<cr> This new command is sent which would then cause the servo to rotate from -420.0 degrees to 480.0 degrees (blue arrow), which would be a total of 900 degrees of clockwise rotation, or 2.5 complete rotations.
125
126 #1D3300<cr> would cause the servo to rotate from 480.0 degrees to 330.0 degrees (yellow arrow).
127
128 If / once the servo loses power or is power cycled, it also loses the virtual position associated with that session. For example, if the virtual position was 480.0 degrees before power is cycled, upon power up the servo's position will be read as +120.0 degrees from zero (assuming center position has not been modified).
129 )))
130
131 = Command List =
132
133 == Regular ==
134
135 |= #|=Description|=Mod|= Action|= Query|= Config|=Session|= RC|= Serial|= Units|=(% style="width: 510px;" %) Notes|=(% style="width: 113px;" %)Default Value
136 | 1|[[**L**imp>>||anchor="H1.Limp28L29"]]| | L| | | | | ✓|none|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
137 | 2|[[**H**alt & **H**old>>||anchor="H2.Halt26Hold28H29"]]| | H| | | | | ✓|none|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
138 | 3|[[**T**imed move>>||anchor="H3.Timedmove28T29modifier"]]|T| | | | | | ✓|milliseconds|(% style="width:510px" %) Modifier only for {P, D, MD}. Time is estimated and can change based on load|(% style="text-align:center; width:113px" %)
139 | 4|[[**S**peed>>||anchor="H4.Speed28S29modifier"]]|S/SD| |QS| | | | ✓|microseconds per second|(% style="width:510px" %) Modifier only {P}|(% style="text-align:center; width:113px" %)
140 | 5|[[**M**ove in **D**egrees (relative)>>||anchor="H5.28Relative29MoveinDegrees28MD29"]]| | MD| | | | | ✓|tenths of degrees (ex 325 = 32.5 degrees)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
141 | 6|[[**O**rigin Offset>>||anchor="H6.OriginOffsetAction28O29"]]| | O| QO|CO|✓| ✓| ✓|tenths of degrees (ex 91 = 9.1 degrees)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)(((
142 0
143 )))
144 | 7|[[**A**ngular **R**ange>>||anchor="H7.AngularRange28AR29"]]| | AR| QAR| CAR|✓| ✓| ✓|tenths of degrees |(% style="width:510px" %) |(% style="text-align:center; width:113px" %)(((
145 1800
146 )))
147 | 8|[[Position in **P**ulse>>||anchor="H8.PositioninPulse28P29"]]| | P| QP| | | | ✓|microseconds|(% style="width:510px" %)(((
148 Inherited from SSC-32 serial protocol
149 )))|(% style="text-align:center; width:113px" %)
150 | 9|[[Position in **D**egrees>>||anchor="H9.PositioninDegrees28D29"]]| | D| QD / QDT| | | | ✓|tenths of degrees |(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
151 | 10|[[**W**heel mode in **D**egrees>>||anchor="H10.WheelModeinDegrees28WD29"]]| | WD| QWD| | | | ✓|tenths of degrees per second (ex 248 = 24.8 degrees per second)|(% style="width:510px" %)A.K.A. "Speed mode" or "Continuous rotation"|(% style="text-align:center; width:113px" %)
152 | 11|[[**W**heel mode in **R**PM>>||anchor="H11.WheelModeinRPM28WR29"]]| | WR| QWR| | | | ✓|revolutions per minute (rpm)|(% style="width:510px" %)A.K.A. "Speed mode" or "Continuous rotation"|(% style="text-align:center; width:113px" %)
153 | 12|[[Max **S**peed in **D**egrees>>||anchor="H12.MaxSpeedinDegrees28SD29"]]| | SD| QSD|CSD|✓| ✓| ✓|degrees per second (°/s)|(% style="width:510px" %)(((
154 QSD: Add modifier "2" for instantaneous speed.
155
156 SD overwrites SR / CSD overwrites CSR and vice-versa.
157 )))|(% style="text-align:center; width:113px" %)Max per servo
158 | 13|[[Max **S**peed in **R**PM>>||anchor="H13.MaxSpeedinRPM28SR29"]]| | SR| QSR|CSR|✓| ✓| ✓|revolutions per minute (rpm)|(% style="width:510px" %)(((
159 QSR: Add modifier "2" for instantaneous speed
160
161 SR overwrites SD / CSR overwrites CSD and vice-versa.
162 )))|(% style="text-align:center; width:113px" %)Max per servo
163 | 14|[[**LED** Color>>||anchor="H14.LEDColor28LED29"]]| | LED| QLED| CLED|✓| ✓| ✓|none (integer from 0 to 7)|(% style="width:510px" %)0=Off (black); 1=Red 2=Green; 3=Blue; 4=Yellow; 5=Cyan; 6=Magenta; 7=White;|(% style="text-align:center; width:113px" %)0 (OFF)
164 | 15|[[**G**yre direction (**G**)>>||anchor="H15.GyreRotationDirection28G29"]]| | G| QG| CG|✓| ✓| ✓|none |(% style="width:510px" %)Gyre / rotation direction: 1= CW (clockwise) -1 = CCW (counter-clockwise)|(% style="text-align:center; width:113px" %)1
165 | 16|[[**ID** #>>||anchor="H16.IdentificationNumber28ID29"]]| | | QID| CID| | | ✓|none (integer from 0 to 250)|(% style="width:510px" %)Note: ID 254 is a "broadcast" which all servos respond to. |(% style="text-align:center; width:113px" %)0
166 | 17|[[**B**aud rate>>||anchor="H17.BaudRate"]]| | | QB| CB| | | ✓|none (integer)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)115200
167 | 18|//{coming soon}//| | | | | | | | |(% style="width:510px" %) |(% style="text-align:center; width:113px" %)(((
168
169 )))
170 | 19|[[**F**irst Position (**D**eg)>>||anchor="H19.FirstA0Position28Degrees29"]]| | | QFD|CFD|X| ✓| ✓|none |(% style="width:510px" %) |(% style="text-align:center; width:113px" %)No Value
171 | 20|[[**M**odel **S**tring>>||anchor="H20.QueryModelString28QMS29"]]| | | QMS| | | | |none (string)|(% style="width:510px" %) Returns the type of servo (ex: LSS-ST1, LSS-HS1, LSS-HT1)|(% style="text-align:center; width:113px" %)
172 | 21|[[Serial **N**umber>>||anchor="H21.QuerySerialNumber28QN29"]]| | | QN| | | | |none (integer)|(% style="width:510px" %) Returns the unique serial number for that servo|(% style="text-align:center; width:113px" %)
173 | 22|[[**F**irmware version>>||anchor="H22.QueryFirmware28QF29"]]| | | QF| | | | |none (integer)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
174 | 23|[[**Q**uery (gen. status)>>||anchor="H23.QueryStatus28Q29"]]| | | Q| | | | ✓|none (integer from 1 to 8)|(% style="width:510px" %) See command description for details|(% style="text-align:center; width:113px" %)
175 | 24|[[**V**oltage>>||anchor="H24.QueryVoltage28QV29"]]| | | QV| | | | ✓|millivolts (ex 5936 = 5936mV = 5.936V)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
176 | 25|[[**T**emperature>>||anchor="H25.QueryTemperature28QT29"]]| | | QT| | | | ✓|tenths of degrees Celsius|(% style="width:510px" %)Max temp before error: 85°C (servo goes limp)|(% style="text-align:center; width:113px" %)
177 | 26|[[**C**urrent>>||anchor="H26.QueryCurrent28QC29"]]| | | QC| | | | ✓|milliamps (ex 200 = 0.2A)|(% style="width:510px" %) |(% style="text-align:center; width:113px" %)
178 | 27|[[**C**hange to** RC**>>||anchor="H27.ConfigureRCMode28CRC29"]]| | | |CRC|✓| | ✓|none|(% style="width:510px" %)(((
179 Change to RC mode 1 (position) or 2 (wheel).
180 )))|(% style="text-align:center; width:113px" %)Serial
181 | 28|[[**RESET**>>||anchor="H28.RESET"]]| | | | | | | ✓|none|(% style="width:510px" %)Soft reset. See command for details.|(% style="text-align:center; width:113px" %)
182 | 29|[[**DEFAULT**>>||anchor="H29.DEFAULTA026CONFIRM"]]| | | | | | |✓|none|(% style="width:510px" %)Revert to firmware default values. See command for details|(% style="text-align:center; width:113px" %)
183 | 30|[[**UPDATE**>>||anchor="H30.UPDATEA026CONFIRM"]]| | | | | | |✓|none|(% style="width:510px" %)Update firmware. See command for details.|(% style="text-align:center; width:113px" %)
184
185 == Advanced ==
186
187 |= #|=(% style="width: 182px;" %)Description|=(% style="width: 56px;" %)Mod|=(% style="width: 70px;" %) Action|=(% style="width: 71px;" %) Query|=(% style="width: 77px;" %) Config|=(% style="width: 77px;" %)Session|=(% style="width: 56px;" %) RC|=(% style="width: 151px;" %) Serial|= Units|=(% style="width: 510px;" %) Notes
188 | A1|(% style="width:182px" %)[[**A**ngular **S**tiffness>>||anchor="HA1.AngularStiffness28AS29"]]|(% style="width:56px" %) |(% style="width:70px" %)AS|(% style="width:71px" %)QAS|(% style="width:77px" %)CAS|(% style="width:77px" %)✓|(% style="width:56px" %) ✓|(% style="width:151px" %) ✓|none (integer -4 to +4)|(% style="width:510px" %)Suggested values are between 0 to +4
189 | A2|(% style="width:182px" %)[[**A**ngular **H**olding Stiffness>>||anchor="HA2.AngularHoldingStiffness28AH29"]]|(% style="width:56px" %) |(% style="width:70px" %)AH|(% style="width:71px" %)QAH|(% style="width:77px" %)CAH|(% style="width:77px" %)✓|(% style="width:56px" %) |(% style="width:151px" %) ✓|none (integer -10 to +10)|(% style="width:510px" %)Effect is different between serial and RC
190 | A3|(% style="width:182px" %)[[**A**ngular **A**cceleration>>||anchor="HA3:AngularAcceleration28AA29"]]|(% style="width:56px" %) |(% style="width:70px" %)AA|(% style="width:71px" %)QAA|(% style="width:77px" %)CAA|(% style="width:77px" %)✓|(% style="width:56px" %) |(% style="width:151px" %) ✓|degrees per second squared|(% style="width:510px" %)Increments of 10 degrees per second squared
191 | A4|(% style="width:182px" %)[[**A**ngular **D**eceleration>>||anchor="HA4:AngularDeceleration28AD29"]]|(% style="width:56px" %) |(% style="width:70px" %)AD|(% style="width:71px" %)QAD|(% style="width:77px" %)CAD|(% style="width:77px" %)✓|(% style="width:56px" %) |(% style="width:151px" %) ✓|degrees per second squared|(% style="width:510px" %)Increments of 10 degrees per second squared
192 | A5|(% style="width:182px" %)[[**E**nable **M**otion Control>>||anchor="HA5:MotionControl28EM29"]]|(% style="width:56px" %) |(% style="width:70px" %)EM|(% style="width:71px" %)QEM|(% style="width:77px" %) |(% style="width:77px" %) |(% style="width:56px" %) |(% style="width:151px" %) ✓|none|(% style="width:510px" %)EM0 to disable motion control, EM1 to enable
193 | A6|(% style="width:182px" %)[[**C**onfigure **L**ED **B**linking>>||anchor="HA6.ConfigureLEDBlinking28CLB29"]]|(% style="width:56px" %) |(% style="width:70px" %) |(% style="width:71px" %)QLB|(% style="width:77px" %) CLB|(% style="width:77px" %) |(% style="width:56px" %) ✓|(% style="width:151px" %) ✓|none (integer from 0 to 63)|(% style="width:510px" %)(((
194 0=No blinking, 63=Always blink;
195
196 Blink while: 1=Limp; 2=Holding; 4=Accel; 8=Decel; 16=Free 32=Travel;
197 )))
198 | A7|(% style="width:182px" %)[[**C**urrent **H**alt & **H**old>>||anchor="HA7.CurrentHalt26Hold28CH29"]]|(% style="width:56px" %)CH|(% style="width:70px" %) |(% style="width:71px" %) |(% style="width:77px" %) |(% style="width:77px" %)✓|(% style="width:56px" %) |(% style="width:151px" %)✓|milliamps (ex 400 = 0.4A)|(% style="width:510px" %)Modifier for D, MD, WD, WR
199 | A8|(% style="width:182px" %)[[**C**urrent **L**imp>>||anchor="HA8.CurrentLimp28CL29"]]|(% style="width:56px" %)CL|(% style="width:70px" %) |(% style="width:71px" %) |(% style="width:77px" %) |(% style="width:77px" %)✓|(% style="width:56px" %) |(% style="width:151px" %)✓|milliamps (ex 400 = 0.4A)|(% style="width:510px" %)Modifier for D, MD, WD, WR
200
201 == Details - Basic ==
202
203 ====== __1. Limp (**L**)__ ======
204
205 Example: #5L<cr>
206
207 This action causes the servo to go "limp". The microcontroller will still be powered, but the motor will not. As an emergency safety feature, should the robot not be doing what it is supposed to or risks damage, use the broadcast ID to set all servos limp #254L<cr>.
208
209 ====== __2. Halt & Hold (**H**)__ ======
210
211 Example: #5H<cr>
212
213 This action overrides whatever the servo might be doing at the time the command is received (accelerating, moving continuously etc.) and causes it to stop immediately and hold that angular position.
214
215 ====== __3. Timed move (**T**) modifier__ ======
216
217 Example: #5P1500T2500<cr>
218
219 Timed move can be used only as a modifier for a position (P, D, MD) actions. The units are in milliseconds, so a timed move of 2500 milliseconds would cause the servo to rotate from its current position to the desired position in 2.5 seconds. The onboard controller will attempt to ensure that the move is performed entirely at the desired velocity, though differences in torque may cause it to not be exact. This command is in place to ensure backwards compatibility with the SSC-32 / 32U protocol.
220
221 Note: If the calculated speed at which a servo must rotate for a timed move is greater than its maximum speed (which depends on voltage and load), then it will move at its maximum speed, and the time of the move may be longer than requested.
222
223 ====== __4. Speed (**S**) modifier__ ======
224
225 Example: #5P1500S750<cr>
226
227 This command is a modifier only for a position (P) action and determines the speed of the move in microseconds per second. A speed of 750 microseconds would cause the servo to rotate from its current position to the desired position at a speed of 750 microseconds per second. This command is in place to ensure backwards compatibility with the SSC-32 / 32U protocol.
228
229 Query Speed (**QS**)
230
231 Example: #5QS<cr> might return *5QS300<cr>
232
233 This command queries the current speed in microseconds per second.
234
235 ====== __5. (Relative) Move in Degrees (**MD**)__ ======
236
237 Example: #5MD123<cr>
238
239 The relative move command causes the servo to read its current position and move the specified number of tenths of degrees in the corresponding position. For example if the servo is set to rotate CW (default) and an MD command of 123 is sent to the servo, it will cause the servo to rotate clockwise by 12.3 degrees. Negative commands would cause the servo to rotate in the opposite configured direction.
240
241 ====== __6. Origin Offset Action (**O**)__ ======
242
243 Example: #5O2400<cr>
244
245 This command allows you to temporarily change the origin of the servo in relation to the factory zero position for that session. As with all action commands, the setting will be lost upon servo reset / power cycle. Origin offset commands are not cumulative and always relate to factory zero. In the first image, the origin at factory offset '0' (centered).
246
247 [[image:LSS-servo-default.jpg]]
248
249 In the second image, the origin, and the corresponding angular range (explained below) have been shifted by +240.0 degrees:
250
251 [[image:LSS-servo-origin.jpg]]
252
253 Origin Offset Query (**QO**)
254
255 Example: #5QO<cr> Returns: *5QO-13
256
257 This allows you to query the angle (in tenths of degrees) of the origin in relation to the factory zero position. In this example, the new origin is at -1.3 degrees from the factory zero.
258
259 Configure Origin Offset (**CO**)
260
261 Example: #5CO-24<cr>
262
263 This command allows you to change the origin of the servo in relation to the factory zero position in EEPROM. The setting will be saved upon servo reset / power cycle. Origin offset configuration commands are not cumulative and always relate to factory zero. The new origin is also used in RC mode. In the example, the new origin will be at -2.4 degrees from the factory zero.
264
265 ====== __7. Angular Range (**AR**)__ ======
266
267 Example: #5AR1800<cr>
268
269 This command allows you to temporarily change the total angular range of the servo in tenths of degrees. This applies to the Position in Pulse (P) command and RC mode. The default for (P) and RC mode is 1800 (180.0 degrees total, or ±90.0 degrees). The image below shows a standard -180.0 to +180.0 range, with no offset:
270
271 [[image:LSS-servo-default.jpg]]
272
273 Below, the angular range is restricted to 180.0 degrees, or -90.0 to +90.0. The center has remained unchanged.
274
275 [[image:LSS-servo-ar.jpg]]
276
277 Finally, the angular range action command (ex. #5AR1800<cr>) and origin offset action command (ex. #5O-1200<cr>) are used to move both the center and limit the angular range:
278
279 [[image:LSS-servo-ar-o-1.jpg]]
280
281 Query Angular Range (**QAR**)
282
283 Example: #5QAR<cr> might return *5AR1800, indicating the total angular range is 180.0 degrees.
284
285 Configure Angular Range (**CAR**)
286
287 This command allows you to change the total angular range of the servo in tenths of degrees in EEPROM. The setting will be saved upon servo reset / power cycle.
288
289 ====== __8. Position in Pulse (**P**)__ ======
290
291 Example: #5P2334<cr>
292
293 The position in PWM pulses was retained in order to be backward compatible with the SSC-32 / 32U protocol. This relates the desired angle with an RC standard PWM pulse and is further explained in the SSC-32 and SSC-32U manuals found on Lynxmotion.com. Without any modifications to configuration considered, and a ±90.0 degrees standard range where 1500 microseconds is centered, a pulse of 2334 would set the servo to 165.1 degrees. Valid values for P are [500, 2500]. Values outside this range are corrected / restricted to end points.
294
295 Query Position in Pulse (**QP**)
296
297 Example: #5QP<cr> might return *5QP2334
298
299 This command queries the current angular position in PWM "units". The user must take into consideration that the response includes any angular range and origin configurations in order to determine the actual angle. 
300 Valid values for QP are {-500, [500, 2500], -2500}. Values outside the [500, 2500] range are given a negative corresponding end point value to indicate they are out of bounds (note that if the servo is physically located at one of the endpoints, it may return a negative number if it is a fraction of a degree beyond the position).
301
302 ====== __9. Position in Degrees (**D**)__ ======
303
304 Example: #5D1456<cr>
305
306 This moves the servo to an angle of 145.6 degrees, where the center (0) position is centered. Negative values (ex. -176 representing -17.6 degrees) are used. A full circle would be from -1800 to 1800 degrees. A value of 2700 would be the same angle as -900, except the servo would move in a different direction.
307
308 Larger values are permitted and allow for multi-turn functionality using the concept of virtual position.
309
310 Query Position in Degrees (**QD**)
311
312 Example: #5QD<cr> might return *5QD132<cr>
313
314 This means the servo is located at 13.2 degrees.
315
316 (% class="wikigeneratedid" id="H22.QueryTargetPositioninDegrees28QDT29" %)
317 Query Target Position in Degrees (**QDT**)
318
319 Ex: #5QDT<cr> might return *5QDT6783<cr>
320
321 The query target position command returns the target angle during and after an action which results in a rotation of the servo horn. In the example above, the servo is rotating to a virtual position of 678.3 degrees. Should the servo not have a target position or be in wheel mode, it will respond without a number (Ex: *5QDT<cr>).
322
323 ====== __10. Wheel Mode in Degrees (**WD**)__ ======
324
325 Ex: #5WD900<cr>
326
327 This command sets the servo to wheel mode where it will rotate in the desired direction at the selected speed. The example above would have the servo rotate at 90.0 degrees per second clockwise (assuming factory default configurations).
328
329 Query Wheel Mode in Degrees (**QWD**)
330
331 Ex: #5QWD<cr> might return *5QWD900<cr>
332
333 The servo replies with the angular speed in tenths of degrees per second. A negative sign would indicate the opposite direction (for factory default a negative value would be counter clockwise).
334
335 ====== __11. Wheel Mode in RPM (**WR**)__ ======
336
337 Ex: #5WR40<cr>
338
339 This command sets the servo to wheel mode where it will rotate in the desired direction at the selected rpm. Wheel mode (a.k.a. "continuous rotation") has the servo operate like a geared DC motor. The servo's maximum rpm cannot be set higher than its physical limit at a given voltage. The example above would have the servo rotate at 40 rpm clockwise (assuming factory default configurations).
340
341 Query Wheel Mode in RPM (**QWR**)
342
343 Ex: #5QWR<cr> might return *5QWR40<cr>
344
345 The servo replies with the angular speed in rpm. A negative sign would indicate the opposite direction (for factory default a negative value would be counter clockwise).
346
347 ====== __12. Max Speed in Degrees (**SD**)__ ======
348
349 Ex: #5SD1800<cr>
350
351 This command sets the servo's maximum speed for motion commands in tenths of degrees per second for that session. In the example above, the servo's maximum speed for that session would be set to 180.0 degrees per second. The servo's maximum speed cannot be set higher than its physical limit at a given voltage. The SD action command overrides CSD (described below) for that session. Upon reset or power cycle, the servo reverts to the value associated with CSD as described below. Note that SD and SR (described below) are effectively the same, but allow the user to specify the speed in either unit. The last command (either SR or SD) received is what the servo uses for that session.
352
353 Query Speed in Degrees (**QSD**)
354
355 Ex: #5QSD<cr> might return *5QSD1800<cr>
356
357 By default QSD will return the current session value, which is set to the value of CSD as reset/power cycle and changed whenever an SD/SR command is processed.
358 If #5QSD1<cr> is sent, the configured maximum speed (CSD value) will be returned instead. You can also query the current speed using "2" and the current target travel speed using "3". See the table below for an example:
359
360 |**Command sent**|**Returned value (1/10 °)**
361 |ex: #5QSD<cr>|Session value for maximum speed (set by latest SD/SR command)
362 |ex: #5QSD1<cr>|Configured maximum speed in EEPROM (set by CSD/CSR)
363 |ex: #5QSD2<cr>|Instantaneous speed (same as QWD)
364 |ex: #5QSD3<cr>|Target travel speed
365
366 Configure Speed in Degrees (**CSD**)
367
368 Ex: #5CSD1800<cr>
369
370 Using the CSD command sets the servo's maximum speed which is saved in EEPROM. In the example above, the servo's maximum speed will be set to 180.0 degrees per second. When the servo is powered on (or after a reset), the CSD value is used. Note that CSD and CSR (described below) are effectively the same, but allow the user to specify the speed in either unit. The last command (either CSR or CSD) is what the servo uses for that session.
371
372 ====== __13. Max Speed in RPM (**SR**)__ ======
373
374 Ex: #5SD45<cr>
375
376 This command sets the servo's maximum speed for motion commands in rpm for that session. In the example above, the servo's maximum speed for that session would be set to 45rpm. The servo's maximum speed cannot be set higher than its physical limit at a given voltage. SD overrides CSD (described below) for that session. Upon reset or power cycle, the servo reverts to the value associated with CSD as described below. Note that SD (described above) and SR are effectively the same, but allow the user to specify the speed in either unit. The last command (either SR or SD) received is what the servo uses for that session.
377
378 Query Speed in Degrees (**QSR**)
379
380 Ex: #5QSR<cr> might return *5QSR45<cr>
381
382 By default QSR will return the current session value, which is set to the value of CSR as reset/power cycle and changed whenever an SD/SR command is processed.
383 If #5QSR1<cr> is sent, the configured maximum speed (CSR value) will be returned instead. You can also query the current speed using "2" and the current target travel speed using "3". See the table below for an example:
384
385 |**Command sent**|**Returned value (1/10 °)**
386 |ex: #5QSR<cr>|Session value for maximum speed (set by latest SD/SR command)
387 |ex: #5QSR1<cr>|Configured maximum speed in EEPROM (set by CSD/CSR)
388 |ex: #5QSR2<cr>|Instantaneous speed (same as QWR)
389 |ex: #5QSR3<cr>|Target travel speed
390
391 Configure Speed in RPM (**CSR**)
392
393 Ex: #5CSR45<cr>
394
395 Using the CSR command sets the servo's maximum speed which is saved in EEPROM. In the example above, the servo's maximum speed will be set to 45rpm. When the servo is powered on (or after a reset), the CSR value is used. Note that CSD and CSR are effectively the same, but allow the user to specify the speed in either unit. The last command (either CSR or CSD) received is what the servo uses for that session.
396
397 ====== __14. LED Color (**LED**)__ ======
398
399 Ex: #5LED3<cr>
400
401 This action sets the servo's RGB LED color for that session.The LED can be used for aesthetics, or (based on user code) to provide visual status updates. Using timing can create patterns.
402
403 0=Off (black); 1=Red 2=Green; 3=Blue; 4=Yellow; 5=Cyan; 6=Magenta; 7=White;
404
405 Query LED Color (**QLED**)
406
407 Ex: #5QLED<cr> might return *5QLED5<cr>
408
409 This simple query returns the indicated servo's LED color.
410
411 Configure LED Color (**CLED**)
412
413 Configuring the LED color via the CLED command sets the startup color of the servo after a reset or power cycle. Note that it also changes the session's LED color immediately as well.
414
415 ====== __15. Gyre Rotation Direction (**G**)__ ======
416
417 "Gyre" is defined as a circular course or motion. The effect of changing the gyre direction is as if you were to use a mirror image of a circle. CW = 1; CCW = -1. The factory default is clockwise (CW).
418
419 Ex: #5G-1<cr>
420
421 This command will cause servo #5's positions to be inverted, effectively causing the servo to rotate in the opposite direction given the same command. For example in a 2WD robot, servos are often physically installed back to back, therefore setting one of the servos to a negative gyration, the same wheel command (ex WR30) to both servos will cause the robot to move forward or backward rather than rotate.
422
423 Query Gyre Direction (**QG**)
424
425 Ex: #5QG<cr> might return *5QG-1<cr>
426
427 The value returned above means the servo is in a counter-clockwise gyration.
428
429 Configure Gyre (**CG**)
430
431 Ex: #5CG-1<cr>
432
433 This changes the gyre direction as described above and also writes to EEPROM.
434
435 ====== __16. Identification Number (**ID**)__ ======
436
437 A servo's identification number cannot be set "on the fly" and must be configured via the CID command described below. The factory default ID number for all servos is 0. Since smart servos are intended to be daisy chained, in order to respond differently from one another, the user must set different identification numbers. Servos with the same ID and baud rate will all receive and react to the same commands (assuming same baud rate).
438
439 Query Identification (**QID**)
440
441 EX: #254QID<cr> might return *QID5<cr>
442
443 When using the query ID command, it is best to only have one servo connected and thus receive only one reply. This is useful when you are not sure of the servo's ID, but don't want to change it. Using the broadcast command (ID 254) with only one servo will have that servo reply with its ID number (assuming the query is sent . Alternatively, pushing the button upon startup and temporarily setting the servo ID to 255 will still result in the servo responding with its "real" ID.
444
445 Configure ID (**CID**)
446
447 Ex: #4CID5<cr>
448
449 Setting a servo's ID in EEPROM is done via the CID command. All servos connected to the same serial bus will be assigned that ID. In most situations each servo must be set a unique ID, which means each servo must be connected individually to the serial bus and receive a unique CID number. It is best to do this before the servos are added to an assembly. Numbered stickers are provided to distinguish each servo after their ID is set, though you are free to use whatever alternative method you like. The servo must be RESET or power cycled in order for the new ID to take effect.
450
451 ====== __17. Baud Rate__ ======
452
453 A servo's baud rate cannot be set "on the fly" and must be configured via the CB command described below. The factory default baud rate for all servos is 115200. Since smart servos are intended to be daisy chained, in order to respond to the same serial bus, all servos in a project should ideally be set to the same baud rate. Setting different baud rates will have the servos respond differently and may create issues. Available baud rates are: 9600 bps, 19200 bps, 38400 bps, 57600 bps, 115.2 kbps, 230.4 kbps, 250.0 kbps, 460.8 kbps, 500.0 kbps. Servos are shipped with a baud rate set to 115200. The baud rates are currently restricted to those above.
454
455 Query Baud Rate (**QB**)
456
457 Ex: #5QB<cr> might return *5QB115200<cr>
458
459 Since the command to query the baud rate must be done at the servo's existing baud rate, it can simply be used to confirm the CB configuration command was correctly received before the servo is power cycled and the new baud rate takes effect.
460
461 Configure Baud Rate (**CB**)
462
463 Important Note: the servo's current session retains the given baud rate and the new baud rate will only take effect when the servo is power cycled / RESET.
464
465 Ex: #5CB9600<cr>
466
467 Sending this command will change the baud rate associated with servo ID 5 to 9600 bits per second.
468
469 ====== __18. {//Coming soon//}__ ======
470
471 Command coming soon....
472
473 ====== __19. First Position (Degrees)__ ======
474
475 In certain cases, a user might want to have the servo move to a specific angle upon power up; we refer to this as "first position" (a.k.a. "initial position"). The factory default has no first position value stored in EEPROM and therefore upon power up, the servo remains limp until a position (or hold command) is assigned. Note that the number should be restricted to -1790 (-179.0 degrees) to +1790 (179.0 degrees) and values beyond this will be changed to 1800.
476
477 Query First Position in Degrees (**QFD**)
478
479 Ex: #5QFD<cr> might return *5QFD64<cr>
480
481 The reply above indicates that servo with ID 5 has a first position pulse of 1550 microseconds. If there is no first position value stored, the reply will be DIS
482
483 Configure First Position in Degrees (**CFD**)
484
485 Ex: #5CD64<cr>
486
487 This configuration command means the servo, when set to smart mode, will immediately move to 6.4 degrees upon power up. Sending a CFD command without a number (Ex. #5CFD<cr>) results in the servo remaining limp upon power up. In order to remove the first position, send no value, ex: #5CFD<cr>
488
489 ====== __20. Query Model String (**QMS**)__ ======
490
491 Ex: #5QMS<cr> might return *5QMSLSS-HS1<cr>
492
493 This reply means the servo model is LSS-HS1, meaning a high speed servo, first revision.
494
495 ====== __21. Query Serial Number (**QN**)__ ======
496
497 Ex: #5QN<cr> might return *5QN12345678<cr>
498
499 The number in the response (12345678) would be the servo's serial number which is set and should not be changed by the user.
500
501 ====== __22. Query Firmware (**QF**)__ ======
502
503 Ex: #5QF<cr> might return *5QF411<cr>
504
505 The number in the reply represents the firmware version, in this example being 411.
506
507 ====== __23. Query Status (**Q**)__ ======
508
509 The status query described what the servo is currently doing. The query returns an integer which must be looked up in the table below. Use the CLB advanced command to have the LED blink for certain statuses.
510
511 Ex: #5Q<cr> might return *5Q6<cr>, which indicates the motor is holding a position.
512
513 |***Value returned (Q)**|**Status**|**Detailed description**
514 |ex: *5Q0<cr>|0: Unknown|LSS is unsure / unknown state
515 |ex: *5Q1<cr>|1: Limp|Motor driving circuit is not powered and horn can be moved freely
516 |ex: *5Q2<cr>|2: Free moving|Motor driving circuit is not powered and horn can be moved freely
517 |ex: *5Q3<cr>|3: Accelerating|Increasing speed from rest (or previous speed) towards travel speed
518 |ex: *5Q4<cr>|4: Traveling|Moving at a stable speed
519 |ex: *5Q5<cr>|5: Decelerating|Decreasing from travel speed towards final position.
520 |ex: *5Q6<cr>|6: Holding|Keeping current position
521 |ex: *5Q7<cr>|7: Outside limits|{More details coming soon}
522 |ex: *5Q8<cr>|8: Stuck|Motor cannot perform request movement at current speed setting
523 |ex: *5Q9<cr>|9: Blocked|Similar to stuck, but the motor is at maximum duty and still cannot move (i.e.: stalled)
524 |ex: *5Q10<cr>|10: Safe Mode|(((
525 A safety limit has been exceeded (temperature, peak current or extended high current draw).
526
527 Send a Q1 command to know which limit has been reached (described below).
528 )))
529
530 (% class="wikigeneratedid" %)
531 If a safety limit has been reached and exceeded, the LED will flash red and the servo will stop providing torque (no longer react to commands which cause the motor to rotate). In order to determine which limit has been reached, send a Q1 command. The servo must be RESET in order to return to normal operation, though if a limit is still detected (for example the servo is still too hot), it will revert back to Safe Mode.
532
533 |***Value returned (Q1)**|**Status**|**Detailed description**
534 |ex: *5Q0<cr>|No limits have been passed|Nothing is wrong
535 |ex: *5Q1<cr>|Current limit has been passed|Something cause the current to either spike, or remain too high for too long
536 |ex: *5Q2<cr>|Input voltage detected is below or above acceptable range|Check the voltage of your batteries or power source
537 |ex: *5Q3<cr>|Temperature limit has been reached|The servo is too hot to continue operating safely.
538
539 ====== __24. Query Voltage (**QV**)__ ======
540
541 Ex: #5QV<cr> might return *5QV11200<cr>
542
543 The number returned has one decimal, so in the case above, servo with ID 5 has an input voltage of 11.2V (perhaps a three cell LiPo battery).
544
545 ====== __25. Query Temperature (**QT**)__ ======
546
547 Ex: #5QT<cr> might return *5QT564<cr>
548
549 The units are in tenths of degrees Celcius, so in the example above, the servo's internal temperature is 56.4 degrees C. To convert from degrees Celcius to degrees Farenheit, multiply by 1.8 and add 32. Therefore 56.4C = 133.52F.
550
551 ====== __26. Query Current (**QC**)__ ======
552
553 Ex: #5QC<cr> might return *5QC140<cr>
554
555 The units are in milliamps, so in the example above, the servo is consuming 140mA, or 0.14A.
556
557 ====== __27. Configure RC Mode (**CRC**)__ ======
558
559 This command puts the servo into RC mode (position or continuous), where it will only respond to RC pulses. Note that because this is the case, the servo will no longer accept serial commands. The servo can be placed back into smart mode by using the button menu.
560
561 |**Command sent**|**Note**
562 |ex: #5CRC1<cr>|Change to RC position mode.
563 |ex: #5CRC2<cr>|Change to RC continuous (wheel) mode.
564 |ex: #5CRC*<cr>|Where * is any number or value other than 1 or 2 (or no value): stay in smart mode.
565
566 EX: #5CRC2<cr>
567
568 This command would place the servo in RC wheel mode after a RESET or power cycle. Note that after a RESET or power cycle, the servo will be in RC mode and will not reply to serial commands. Using the command #5CRC<cr> or #5CRC3<cr> which requests that the servo remain in serial mode still requires a RESET command.
569
570 Important note:** **To revert from RC mode back to serial mode, the [[LSS - Button Menu>>doc:lynxmotion-smart-servo.lss-button-menu.WebHome]] is required. Should the button be inaccessible (or broken) when the servo is in RC mode and the user needs to change to serial mode, a 5V constant HIGH needs to be sent to the servo's Rx pin (RC PWM pin), ensuring a common GND and wait for 30 seconds. Normal RC PWM pulses should not exceed 2500 milliseconds. After 30 seconds, the servo will interpret this as a desired mode change and change to serial mode. This has been implemented as a fail safe.
571
572 ====== __28. **RESET**__ ======
573
574 Ex: #5RESET<cr> or #5RS<cr>
575
576 This command does a "soft reset" (no power cycle required) and reverts all commands to those stored in EEPROM (i.e. configuration commands).
577 Note: after a RESET command is received the LSS will restart and perform initilization again, making it unavailable on the bus for a bit. See [[Session>>||anchor="HSession"]], note #2 for more details.
578
579 ====== __29. **DEFAULT** & CONFIRM__ ======
580
581 Ex: #5DEFAULT<cr>
582
583 This command sets in motion the reset of all values to the default values included with the version of the firmware installed on that servo. The servo then waits for the CONFIRM command. Any other command received will cause the servo to exit the DEFAULT function.
584
585 EX: #5DEFAULT<cr> followed by #5CONFIRM<cr>
586
587 Since it it not common to have to restore all configurations, a confirmation command is needed after a firmware command is sent. Should any command other than CONFIRM be received by the servo after the firmware command has been received, it will exit the command.
588
589 Note that after the CONFIRM command is sent, the servo will automatically perform a RESET.
590
591 ====== __30. **UPDATE** & CONFIRM__ ======
592
593 Ex: #5UPDATE<cr>
594
595 This command sets in motion the equivalent of a long button press when the servo is not powered in order to enter firmware update mode. This is useful should the button be broken or inaccessible. The servo then waits for the CONFIRM command. Any other command received will cause the servo to exit the UPDATE function.
596
597 EX: #5UPDATE<cr> followed by #5CONFIRM<cr>
598
599 Since it it not common to have to update firmware, a confirmation command is needed after an UPDATE command is sent. Should any command other than CONFIRM be received by the servo after the firmware command has been received, it will leave the firmware action.
600
601 Note that after the CONFIRM command is sent, the servo will automatically perform a RESET.
602
603 == Details - Advanced ==
604
605 The motion controller used in serial mode is not the same as the motion controller use in RC mode. RC mode is intended to add functionality to what would be considered "normal" RC behavior based on PWM input.
606
607 ====== __A1. Angular Stiffness (**AS**)__ ======
608
609 The servo's rigidity / angular stiffness can be thought of as (though not identical to) a damped spring in which the value affects the stiffness and embodies how much, and how quickly the servo tried keep the requested position against changes. There are no units.
610
611 A positive value of "angular stiffness":
612
613 * The more torque will be applied to try to keep the desired position against external input / changes
614 * The faster the motor will reach its intended travel speed and the motor will decelerate faster and nearer to its target position
615
616 A negative value on the other hand:
617
618 * Causes a slower acceleration to the travel speed, and a slower deceleration
619 * Allows the target position to deviate more from its position before additional torque is applied to bring it back
620
621 The default value for stiffness depending on the firmware may be 0 or 1. Greater values produce increasingly erratic behavior and the effect becomes extreme below -4 and above +4. Maximum values are -10 to +10.
622
623 Ex: #5AS-2<cr>
624
625 This reduces the angular stiffness to -2 for that session, allowing the servo to deviate more around the desired position. This can be beneficial in many situations such as impacts (legged robots) where more of a "spring" effect is desired. Upon reset, the servo will use the value stored in memory, based on the last configuration command.
626
627 Ex: #5QAS<cr>
628
629 Queries the value being used.
630
631 Ex: #5CAS<cr>
632
633 Writes the desired angular stiffness value to memory.
634
635 ====== __A2. Angular Holding Stiffness (**AH**)__ ======
636
637 The angular holding stiffness determines the servo's ability to hold a desired position under load. The default value for stiffness depending on the firmware may be 0 or 1. Greater values produce increasingly erratic behavior and the effect becomes extreme below -4 and above +4. Maximum values are -10 to +10. Note that when  considering altering a stiffness value, the end effect depends on the mode being tested.
638
639 Ex: #5AH3<cr>
640
641 This sets the holding stiffness for servo #5 to 3 for that session.
642
643 Query Angular Hold Stiffness (**QAH**)
644
645 Ex: #5QAH<cr> might return *5QAH3<cr>
646
647 This returns the servo's angular holding stiffness value.
648
649 Configure Angular Hold Stiffness (**CAH**)
650
651 Ex: #5CAH2<cr>
652
653 This writes the angular holding stiffness of servo #5 to 2 to EEPROM. Note that when  considering altering a stiffness value, the end effect depends on the mode being tested.
654
655 ====== __A3: Angular Acceleration (**AA**)__ ======
656
657 The default value for angular acceleration is 100, which is the same as the maximum deceleration. Accepts values of between 1 and 100. Increments of 10 degrees per second squared.
658
659 Ex: #5AA30<cr>
660
661 Query Angular Acceleration (**QAD**)
662
663 Ex: #5QA<cr> might return *5QA30<cr>
664
665 Configure Angular Acceleration (**CAD**)
666
667 Ex: #5CA30<cr>
668
669 ====== __A4: Angular Deceleration (**AD**)__ ======
670
671 The default value for angular deceleration is 100, which is the same as the maximum acceleration. Values between 1 and 15 have the greatest impact.
672
673 Ex: #5AD8<cr>
674
675 Query Angular Deceleration (**QAD**)
676
677 Ex: #5QD<cr> might return *5QD8<cr>
678
679 Configure Angular Deceleration (**CAD**)
680
681 Ex: #5CD8<cr>
682
683 ====== __A5: Motion Control (**EM**)__ ======
684
685 The command EM0 disables use of the motion controller (acceleration, velocity / travel, deceleration). As such, the servo will move at full speed for all motion commands. The command EM1 enables use of the motion controller.
686
687 Note that if the modifiers S or T are used, it is assumed that motion control is desired, and for that command, EM1 will be used.
688
689 ====== __A6. Configure LED Blinking (**CLB**)__ ======
690
691 This command allows you to control when the RGB LED will blink the user set color (see [[16. RGB LED>>||anchor="H16.RGBLED28LED29"]] for details). This is very useful when visually seeing what the servo is doing. You can turn on or off blinking for various LSS status. The command requires that the servo be RESET. Here is the list and their associated value:
692
693 (% style="width:195px" %)
694 |(% style="width:134px" %)**Blink While:**|(% style="width:58px" %)**#**
695 |(% style="width:134px" %)No blinking|(% style="width:58px" %)0
696 |(% style="width:134px" %)Limp|(% style="width:58px" %)1
697 |(% style="width:134px" %)Holding|(% style="width:58px" %)2
698 |(% style="width:134px" %)Accelerating|(% style="width:58px" %)4
699 |(% style="width:134px" %)Decelerating|(% style="width:58px" %)8
700 |(% style="width:134px" %)Free|(% style="width:58px" %)16
701 |(% style="width:134px" %)Travelling|(% style="width:58px" %)32
702 |(% style="width:134px" %)Always blink|(% style="width:58px" %)63
703
704 To set blinking, use CLB with the value of your choosing. To activate blinking in multiple status, simply add together the values of the corresponding status. See examples below:
705
706 Ex: #5CLB0<cr> to turn off all blinking (LED always solid)
707 Ex: #5CLB1<cr> only blink when limp (1)
708 Ex: #5CLB2<cr> only blink when holding (2)
709 Ex: #5CLB12<cr> only blink when accel or decel (accel 4 + decel 8 = 12)
710 Ex: #5CLB48<cr> only blink when free or travel (free 16 + travel 32 = 48)
711 Ex: #5CLB63<cr> blink in all status (1 + 2 + 4 + 8 + 16 + 32)
712
713 RESETTING the servo is needed.
714
715 ====== __A7. Current Halt & Hold (**CH**)__ ======
716
717 This modifier, released in firmware v367, can be added to the following actions: D; MD; WD; WR.
718
719 Ex: #5D1423CH400<cr>
720
721 This has servo with ID 5 move to 142.3 degrees but, should it detect a current of 400mA or higher before it reaches the desired position, will immediately halt and hold position.
722
723 ====== __A8. Current Limp (**CL**)__ ======
724
725 This modifier, released in firmware v367, can be added to the following actions: D; MD; WD; WR.
726
727 Ex: #5D1423CH400<cr>
728
729 This has servo with ID 5 move to 142.3 degrees but, should it detect a current of 400mA or higher before it reaches the desired position, will immediately go limp.
730
731 = RGB LED Patterns =
732
733 The LED patterns below do not include those which are part of the button menu, which can be found here: [[LSS Button Menu>>doc:lynxmotion-smart-servo.lss-button-menu.WebHome]]
734
735 [[image:LSS - LED Patterns.png]]
Copyright RobotShop 2018