moteus 0.3.58__py3-none-any.whl → 0.3.60__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
moteus/__init__.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/aioserial.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/aiostream.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -1,4 +1,4 @@
1
- # Copyright 2019-2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/command.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020-2021 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/export.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/fdcanusb.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020-2021 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -173,8 +173,11 @@ class Fdcanusb:
173
173
  bus_id = (command.destination |
174
174
  (0x8000 if command.reply_required else 0) |
175
175
  (command.can_prefix << 16))
176
+ hexdata = _hexify(command.data)
177
+ on_wire_size = self._round_up_dlc(len(command.data))
178
+ hexdata += '50' * (on_wire_size - len(command.data))
176
179
  cmd = "can send {:04x} {}{}\n".format(
177
- bus_id, _hexify(command.data), self._send_flags).encode('latin1')
180
+ bus_id, hexdata, self._send_flags).encode('latin1')
178
181
  self._serial.write(cmd)
179
182
  if self._debug_log:
180
183
  self._debug_log.write(f'{time.time()} > '.encode('latin1') +
@@ -197,3 +200,22 @@ class Fdcanusb:
197
200
  message.data = _dehexify(fields[2])
198
201
  message.arbitration_id = int(fields[1], 16)
199
202
  return message
203
+
204
+ def _round_up_dlc(self, size):
205
+ if size <= 8:
206
+ return size
207
+ if size <= 12:
208
+ return 12
209
+ if size <= 16:
210
+ return 16
211
+ if size <= 20:
212
+ return 20
213
+ if size <= 24:
214
+ return 24
215
+ if size <= 32:
216
+ return 32
217
+ if size <= 48:
218
+ return 48
219
+ if size <= 64:
220
+ return 64
221
+ return size
moteus/moteus.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020-2022 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -14,6 +14,7 @@
14
14
 
15
15
  import asyncio
16
16
  import argparse
17
+ import copy
17
18
  import enum
18
19
  import importlib_metadata
19
20
  import io
@@ -617,12 +618,15 @@ class Controller:
617
618
  self.transport = get_singleton_transport()
618
619
  return self.transport
619
620
 
620
- def _make_query_data(self):
621
+ def _make_query_data(self, query_resolution=None):
622
+ if query_resolution is None:
623
+ query_resolution = self.query_resolution
624
+
621
625
  expected_reply_size = 0
622
626
 
623
627
  buf = io.BytesIO()
624
628
  writer = Writer(buf)
625
- qr = self.query_resolution
629
+ qr = query_resolution
626
630
  c1 = mp.WriteCombiner(writer, 0x10, int(Register.MODE), [
627
631
  qr.mode,
628
632
  qr.position,
@@ -672,21 +676,37 @@ class Controller:
672
676
 
673
677
  return buf.getvalue(), expected_reply_size
674
678
 
675
- def _make_command(self, *, query, source=0):
679
+ def _format_query(self, query, query_override, data_buf, result):
680
+ if query_override is not None:
681
+ query_data, expected_reply_size = \
682
+ self._make_query_data(query_override)
683
+ data_buf.write(query_data)
684
+ result.expected_reply_size = expected_reply_size
685
+ elif query:
686
+ data_buf.write(self._query_data)
687
+ result.expected_reply_size = self._default_query_reply_size
688
+
689
+ def _make_command(self, *, query, query_override=None, source=0):
676
690
  result = cmd.Command()
677
691
 
678
692
  result.destination = self.id
679
693
  result.source = source
680
- result.reply_required = query
694
+ result.reply_required = query or (query_override is not None)
681
695
  result.parse = self._parser
682
696
  result.can_prefix = self._can_prefix
683
697
  result.expected_reply_size = self._default_query_reply_size if query else 0
684
698
 
685
699
  return result
686
700
 
687
- def make_query(self):
688
- result = self._make_command(query=True)
689
- result.data = self._query_data
701
+ def make_query(self, query_override=None):
702
+ result = self._make_command(
703
+ query=True, query_override=query_override)
704
+ if query_override:
705
+ result.data, result.expected_reply_size = \
706
+ self._make_query_data(query_override)
707
+ else:
708
+ result.data = self._query_data
709
+ result.expected_reply_size = self._default_query_reply_size
690
710
  return result;
691
711
 
692
712
  async def query(self, **kwargs):
@@ -718,11 +738,12 @@ class Controller:
718
738
  async def custom_query(self, *args, **kwargs):
719
739
  return await self.execute(self.make_custom_query(*args, **kwargs))
720
740
 
721
- def make_stop(self, *, query=False):
741
+ def make_stop(self, *, query=False, query_override=None):
722
742
  """Return a moteus.Command structure with data necessary to send a
723
743
  stop mode command."""
724
744
 
725
- result = self._make_command(query=query)
745
+ result = self._make_command(
746
+ query=query, query_override=query_override)
726
747
 
727
748
  data_buf = io.BytesIO()
728
749
  writer = Writer(data_buf)
@@ -730,8 +751,7 @@ class Controller:
730
751
  writer.write_int8(int(Register.MODE))
731
752
  writer.write_int8(int(Mode.STOPPED))
732
753
 
733
- if query:
734
- data_buf.write(self._query_data)
754
+ self._format_query(query, query_override, data_buf, result)
735
755
 
736
756
  result.data = data_buf.getvalue()
737
757
 
@@ -743,12 +763,14 @@ class Controller:
743
763
  def make_set_output(self, *,
744
764
  position=0.0,
745
765
  query=False,
766
+ query_override=None,
746
767
  cmd=None
747
768
  ):
748
769
  """Return a moteus.Command structure with data necessary to send a
749
770
  set output nearest command."""
750
771
 
751
- result = self._make_command(query=query)
772
+ result = self._make_command(
773
+ query=query, query_override=query_override)
752
774
 
753
775
  data_buf = io.BytesIO()
754
776
  writer = Writer(data_buf)
@@ -756,23 +778,26 @@ class Controller:
756
778
  writer.write_varuint(cmd)
757
779
  writer.write_f32(position)
758
780
 
759
- if query:
760
- data_buf.write(self._query_data)
781
+ self._format_query(query, query_override, data_buf, result)
761
782
 
762
783
  result.data = data_buf.getvalue()
763
784
  return result
764
785
 
765
786
  def make_set_output_nearest(self, *,
766
787
  position=0.0,
767
- query=False):
788
+ query=False,
789
+ query_override=None):
768
790
  return self.make_set_output(
769
- position=position, query=query, cmd=Register.SET_OUTPUT_NEAREST)
791
+ position=position, query=query, query_override=query_override,
792
+ cmd=Register.SET_OUTPUT_NEAREST)
770
793
 
771
794
  def make_set_output_exact(self, *,
772
795
  position=0.0,
773
- query=False):
796
+ query=False,
797
+ query_override=None):
774
798
  return self.make_set_output(
775
- position=position, query=query, cmd=Register.SET_OUTPUT_EXACT)
799
+ position=position, query=query, query_override=query_override,
800
+ cmd=Register.SET_OUTPUT_EXACT)
776
801
 
777
802
  async def set_output(self, *args, cmd=None, **kwargs):
778
803
  return await self.execute(self.make_set_output(**kwargs, cmd=cmd))
@@ -788,15 +813,20 @@ class Controller:
788
813
  # "make/set_rezero".
789
814
  def make_rezero(self, *,
790
815
  rezero=0.0,
791
- query=False):
816
+ query=False,
817
+ query_override=None):
792
818
  return self.make_set_output(
793
- position=rezero, query=query, cmd=Register.SET_OUTPUT_NEAREST)
819
+ position=rezero, query=query, query_override=query_override,
820
+ cmd=Register.SET_OUTPUT_NEAREST)
794
821
 
795
822
  async def set_rezero(self, *args, **kwargs):
796
823
  return await self.execute(self.make_rezero(**kwargs))
797
824
 
798
- def make_require_reindex(self):
799
- result = self._make_command(query=False)
825
+ def make_require_reindex(self,
826
+ query=False,
827
+ query_override=None):
828
+ result = self._make_command(
829
+ query=query, query_override=query_override)
800
830
 
801
831
  data_buf = io.BytesIO()
802
832
  writer = Writer(data_buf)
@@ -807,8 +837,9 @@ class Controller:
807
837
  result.data = data_buf.getvalue()
808
838
  return result
809
839
 
810
- async def set_require_reindex(self):
811
- return await self.execute(self.make_require_reindex())
840
+ async def set_require_reindex(self, query=False, query_override=None):
841
+ return await self.execute(self.make_require_reindex(
842
+ query=query, query_override=query_override))
812
843
 
813
844
  def make_position(self,
814
845
  *,
@@ -823,11 +854,13 @@ class Controller:
823
854
  velocity_limit=None,
824
855
  accel_limit=None,
825
856
  fixed_voltage_override=None,
826
- query=False):
857
+ query=False,
858
+ query_override=None):
827
859
  """Return a moteus.Command structure with data necessary to send a
828
860
  position mode command with the given values."""
829
861
 
830
- result = self._make_command(query=query)
862
+ result = self._make_command(
863
+ query=query, query_override=query_override)
831
864
 
832
865
  pr = self.position_resolution
833
866
  resolutions = [
@@ -877,8 +910,7 @@ class Controller:
877
910
  if combiner.maybe_write():
878
911
  writer.write_voltage(fixed_voltage_override, pr.fixed_voltage_override)
879
912
 
880
- if query:
881
- data_buf.write(self._query_data)
913
+ self._format_query(query, query_override, data_buf, result)
882
914
 
883
915
  result.data = data_buf.getvalue()
884
916
 
@@ -887,16 +919,51 @@ class Controller:
887
919
  async def set_position(self, *args, **kwargs):
888
920
  return await self.execute(self.make_position(**kwargs))
889
921
 
922
+ async def set_position_wait_complete(
923
+ self,
924
+ period_s=0.025,
925
+ query_override=None,
926
+ *args, **kwargs):
927
+ """Repeatedly send a position mode command to a device until it
928
+ reports that the trajectory has been completed.
929
+
930
+ If the controller is unresponsive, this method will never return.
931
+ """
932
+
933
+ if query_override is None:
934
+ query_override = copy.deepcopy(self.query_resolution)
935
+ else:
936
+ query_override = copy.deepcopy(query_override)
937
+
938
+ query_override.trajectory_complete = mp.INT8
939
+
940
+ count = 2
941
+ while True:
942
+ result = await self.set_position(
943
+ query_override=query_override, *args, **kwargs)
944
+
945
+ if result is not None:
946
+ count = max(count - 1, 0)
947
+
948
+ if (count == 0 and
949
+ result is not None and
950
+ result.values[Register.TRAJECTORY_COMPLETE]):
951
+ return result
952
+
953
+ await asyncio.sleep(period_s)
954
+
890
955
  def make_vfoc(self,
891
956
  *,
892
957
  theta,
893
958
  voltage,
894
959
  theta_rate=0.0,
895
- query=False):
960
+ query=False,
961
+ query_override=None):
896
962
  """Return a moteus.Command structure with data necessary to send a
897
963
  voltage mode FOC command."""
898
964
 
899
- result = self._make_command(query=query)
965
+ result = self._make_command(
966
+ query=query, query_override=query_override)
900
967
  cr = self.vfoc_resolution
901
968
  resolutions = [
902
969
  cr.theta if theta is not None else mp.IGNORE,
@@ -932,8 +999,7 @@ class Controller:
932
999
  if combiner.maybe_write():
933
1000
  writer.write_velocity(theta_rate / math.pi, cr.theta_rate)
934
1001
 
935
- if query:
936
- data_buf.write(self._query_data)
1002
+ self._format_query(query, query_override, data_buf, result)
937
1003
 
938
1004
  result.data = data_buf.getvalue()
939
1005
 
@@ -946,12 +1012,14 @@ class Controller:
946
1012
  *,
947
1013
  d_A,
948
1014
  q_A,
949
- query=False):
1015
+ query=False,
1016
+ query_override=None):
950
1017
  """Return a moteus.Command structure with data necessary to send a
951
1018
  current mode command.
952
1019
  """
953
1020
 
954
- result = self._make_command(query=query)
1021
+ result = self._make_command(
1022
+ query=query, query_override=query_override)
955
1023
  cr = self.current_resolution
956
1024
  resolutions = [
957
1025
  cr.d_A if d_A is not None else mp.IGNORE,
@@ -976,8 +1044,7 @@ class Controller:
976
1044
  if combiner.maybe_write():
977
1045
  writer.write_current(d_A, cr.d_A)
978
1046
 
979
- if query:
980
- data_buf.write(self._query_data)
1047
+ self._format_query(query, query_override, data_buf, result)
981
1048
 
982
1049
  result.data = data_buf.getvalue()
983
1050
 
@@ -997,11 +1064,13 @@ class Controller:
997
1064
  maximum_torque=None,
998
1065
  stop_position=None,
999
1066
  watchdog_timeout=None,
1000
- query=False):
1067
+ query=False,
1068
+ query_override=None):
1001
1069
  """Return a moteus.Command structure with data necessary to send a
1002
1070
  within mode command with the given values."""
1003
1071
 
1004
- result = self._make_command(query=query)
1072
+ result = self._make_command(
1073
+ query=query, query_override=query_override)
1005
1074
 
1006
1075
  pr = self.position_resolution
1007
1076
  resolutions = [
@@ -1040,8 +1109,7 @@ class Controller:
1040
1109
  if combiner.maybe_write():
1041
1110
  writer.write_time(watchdog_timeout, pr.watchdog_timeout)
1042
1111
 
1043
- if query:
1044
- data_buf.write(self._query_data)
1112
+ self._format_query(query, query_override, data_buf, result)
1045
1113
 
1046
1114
  result.data = data_buf.getvalue()
1047
1115
 
@@ -1050,8 +1118,9 @@ class Controller:
1050
1118
  async def set_stay_within(self, *args, **kwargs):
1051
1119
  return await self.execute(self.make_stay_within(**kwargs))
1052
1120
 
1053
- def make_brake(self, *, query=False):
1054
- result = self._make_command(query=query)
1121
+ def make_brake(self, *, query=False, query_override=None):
1122
+ result = self._make_command(
1123
+ query=query, query_override=query_override)
1055
1124
 
1056
1125
  data_buf = io.BytesIO()
1057
1126
  writer = Writer(data_buf)
@@ -1059,8 +1128,7 @@ class Controller:
1059
1128
  writer.write_int8(int(Register.MODE))
1060
1129
  writer.write_int8(int(Mode.BRAKE))
1061
1130
 
1062
- if query:
1063
- data_buf.write(self._query_data)
1131
+ self._format_query(query, query_override, data_buf, result)
1064
1132
 
1065
1133
  result.data = data_buf.getvalue()
1066
1134
 
@@ -1069,7 +1137,8 @@ class Controller:
1069
1137
  async def set_brake(self, *args, **kwargs):
1070
1138
  return await self.execute(self.make_brake(**kwargs))
1071
1139
 
1072
- def make_write_gpio(self, aux1=None, aux2=None, query=False):
1140
+ def make_write_gpio(self, aux1=None, aux2=None,
1141
+ query=False, query_override=None):
1073
1142
  """Return a moteus.Command structure with data necessary to set one or
1074
1143
  more GPIO registers.
1075
1144
 
@@ -1077,7 +1146,8 @@ class Controller:
1077
1146
  significant bit is pin 0 on the respective port.
1078
1147
  """
1079
1148
 
1080
- result = self._make_command(query=query)
1149
+ result = self._make_command(
1150
+ query=query, query_override=query_override)
1081
1151
 
1082
1152
  data_buf = io.BytesIO()
1083
1153
  writer = Writer(data_buf)
@@ -1093,8 +1163,7 @@ class Controller:
1093
1163
  if combiner.maybe_write():
1094
1164
  writer.write_int8(aux2)
1095
1165
 
1096
- if query:
1097
- data_buf.write(self._query_data)
1166
+ self._format_query(query, query_override, data_buf, result)
1098
1167
 
1099
1168
  result.data = data_buf.getvalue()
1100
1169
  return result
moteus/moteus_tool.py CHANGED
@@ -1,6 +1,6 @@
1
1
  #!/usr/bin/python3 -B
2
2
 
3
- # Copyright 2019-2022 Josh Pieper, jjp@pobox.com.
3
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
4
4
  #
5
5
  # Licensed under the Apache License, Version 2.0 (the "License");
6
6
  # you may not use this file except in compliance with the License.
@@ -560,6 +560,27 @@ class Stream:
560
560
  await self.command("conf write")
561
561
  await self.command(f"d rezero {value}")
562
562
 
563
+ async def do_restore_config(self, config_file):
564
+ errors = []
565
+
566
+ with open(config_file, "r") as fp:
567
+ for line in fp.readlines():
568
+ if '#' in line:
569
+ line = line[0:line.index('#')]
570
+ line = line.rstrip()
571
+ if len(line) == 0:
572
+ continue
573
+
574
+ try:
575
+ await self.command(f'conf set {line}'.encode('latin1'))
576
+ except moteus.CommandError as ce:
577
+ errors.append(line)
578
+
579
+ if len(errors):
580
+ print("\nSome config could not be set:")
581
+ for line in errors:
582
+ print(f" {line}")
583
+ print()
563
584
 
564
585
  async def do_write_config(self, config_file):
565
586
  fp = open(config_file, "rb")
@@ -1532,6 +1553,8 @@ class Runner:
1532
1553
  await stream.do_set_offset(0.0)
1533
1554
  elif self.args.set_offset:
1534
1555
  await stream.do_set_offset(self.args.set_offset)
1556
+ elif self.args.restore_config:
1557
+ await stream.do_restore_config(self.args.restore_config)
1535
1558
  elif self.args.write_config:
1536
1559
  await stream.do_write_config(self.args.write_config)
1537
1560
  elif self.args.flash:
@@ -1569,6 +1592,8 @@ async def async_main():
1569
1592
  help='create a serial console')
1570
1593
  group.add_argument('--dump-config', action='store_true',
1571
1594
  help='emit all configuration to the console')
1595
+ group.add_argument('--restore-config', metavar='FILE',
1596
+ help='restore a config saved with --dump-config')
1572
1597
  group.add_argument('--write-config', metavar='FILE',
1573
1598
  help='write the given configuration')
1574
1599
  group.add_argument('--flash', metavar='FILE',
moteus/multiplex.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/pythoncan.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -87,10 +87,13 @@ class PythonCan:
87
87
  arbitration_id = (command.destination |
88
88
  (0x8000 if reply_required else 0) |
89
89
  (command.can_prefix << 16))
90
+ on_wire_size = self._round_up_dlc(len(command.data))
91
+ full_message = (command.data +
92
+ bytes([0x50]) * (on_wire_size - len(command.data)))
90
93
  message = can.Message(arbitration_id=arbitration_id,
91
94
  is_extended_id=(arbitration_id >= 0x7ff),
92
- dlc=len(command.data),
93
- data=bytearray(command.data),
95
+ dlc=on_wire_size,
96
+ data=full_message,
94
97
  is_fd=True,
95
98
  bitrate_switch=not self._disable_brs)
96
99
 
@@ -99,3 +102,22 @@ class PythonCan:
99
102
  async def read(self):
100
103
  self._maybe_setup()
101
104
  return await self._reader.get_message()
105
+
106
+ def _round_up_dlc(self, size):
107
+ if size <= 8:
108
+ return size
109
+ if size <= 12:
110
+ return 12
111
+ if size <= 16:
112
+ return 16
113
+ if size <= 20:
114
+ return 20
115
+ if size <= 24:
116
+ return 24
117
+ if size <= 32:
118
+ return 32
119
+ if size <= 48:
120
+ return 48
121
+ if size <= 64:
122
+ return 64
123
+ return size
moteus/reader.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2015-2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/regression.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2019-2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/router.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/transport.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
moteus/version.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -12,4 +12,4 @@
12
12
  # See the License for the specific language governing permissions and
13
13
  # limitations under the License.
14
14
 
15
- VERSION="0.3.58"
15
+ VERSION="0.3.60"
moteus/win32_aioserial.py CHANGED
@@ -1,4 +1,4 @@
1
- # Copyright 2020 Josh Pieper, jjp@pobox.com.
1
+ # Copyright 2023 mjbots Robotic Systems, LLC. info@mjbots.com
2
2
  #
3
3
  # Licensed under the Apache License, Version 2.0 (the "License");
4
4
  # you may not use this file except in compliance with the License.
@@ -1,23 +1,21 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: moteus
3
- Version: 0.3.58
3
+ Version: 0.3.60
4
4
  Summary: moteus brushless controller library and tools
5
5
  Home-page: https://github.com/mjbots/moteus
6
6
  Author: mjbots Robotic Systems
7
7
  Author-email: info@mjbots.com
8
- License: UNKNOWN
9
8
  Keywords: moteus
10
- Platform: UNKNOWN
11
9
  Classifier: Development Status :: 3 - Alpha
12
10
  Classifier: Intended Audience :: Developers
13
11
  Classifier: License :: OSI Approved :: Apache Software License
14
12
  Classifier: Programming Language :: Python :: 3
15
13
  Requires-Python: >=3.7, <4
16
14
  Description-Content-Type: text/markdown
17
- Requires-Dist: importlib-metadata (>=3.6)
18
- Requires-Dist: pyelftools (>=0.26)
19
- Requires-Dist: pyserial (>=3.5)
20
- Requires-Dist: python-can (>=3.3)
15
+ Requires-Dist: pyserial >=3.5
16
+ Requires-Dist: python-can >=3.3
17
+ Requires-Dist: pyelftools >=0.26
18
+ Requires-Dist: importlib-metadata >=3.6
21
19
  Requires-Dist: pywin32 ; platform_system == "Windows"
22
20
 
23
21
  # Python bindings for moteus brushless controller #
@@ -119,5 +117,3 @@ qr.torque = mp.F32
119
117
 
120
118
  c = moteus.Controller(position_resolution=pr, query_resolution=qr)
121
119
  ```
122
-
123
-
@@ -0,0 +1,23 @@
1
+ moteus/__init__.py,sha256=DxasQre5HmK3BS3I35K8GEUvFZF3_OE_hjVzQy-seIE,739
2
+ moteus/aioserial.py,sha256=GeWuvsZKCRrfBN33JZFjtBXPr-0sKpQv9shRn2ulcDA,1079
3
+ moteus/aiostream.py,sha256=YAkVF6QWsA49vqO-GgXEohDghqm_-nnajJzhO_Q9qNQ,3696
4
+ moteus/calibrate_encoder.py,sha256=R3pRgGqrDCcmKQqFE7Fr4p8TSie179iqNfBwEJS3pL0,12416
5
+ moteus/command.py,sha256=UkOsbtkso6Oyex8CfbpAKpBNriik519ymxL86EZGkRs,1169
6
+ moteus/export.py,sha256=vRIfldaqz1eHtWo3993SvatATtu73TZbejL0hzQe8YE,1646
7
+ moteus/fdcanusb.py,sha256=bx72fFRCIlXCZ4xr3_3Tec936E4Y237Y1FaHXGNrSHs,7307
8
+ moteus/moteus.py,sha256=I4zrr1YCIvdbaJbraWsx7k-DMg6_F--Ze66pCBrSt1A,47006
9
+ moteus/moteus_tool.py,sha256=ezp-pLoNpb82myOG0Ud7wVM3rSlgF4ssy9XbGlZsaNs,67745
10
+ moteus/multiplex.py,sha256=LF6MuelzYHqqsCJuCB9YeEyUA03eBaTYRwAVotX3qm8,10120
11
+ moteus/posix_aioserial.py,sha256=3JFiY5p4dtC2ztg6N5SOffnNk9lNcjie02yjD3UlJWo,2971
12
+ moteus/pythoncan.py,sha256=NnmK6MU3jS0Te4DTTFwKCbP2yE5OIwkK37Rv0Yp9nb4,3904
13
+ moteus/reader.py,sha256=H1n3ceItP6xOPqlkSm2sN7uUi7cpCbfvvWHKUCM5luo,11945
14
+ moteus/regression.py,sha256=M5gjDBYJQ64iBXIrvBhMkD8TYhtlnQ85x8U4py0niGA,1196
15
+ moteus/router.py,sha256=501W5GZ12rFoc1lmcH3S7IYsoc-Q_-FJ4B3i37RzE3Q,2061
16
+ moteus/transport.py,sha256=WhkW2G9i25lkOlO55eI5_oXmU0PhDmxTeJ75Sg_7nTI,1021
17
+ moteus/version.py,sha256=vqQpeKWSowRuznC4OyLT1Ds0hCOACtQA3H2rbEaDex4,627
18
+ moteus/win32_aioserial.py,sha256=b6J0YV1q9-rCAmtR4Q0N7mxze3BtILZd2FxU0i9-6mA,1859
19
+ moteus-0.3.60.dist-info/METADATA,sha256=BPaAoS8U70DpapUOiSZs7StyyvVPYG4J4NsKcEFd0A0,3372
20
+ moteus-0.3.60.dist-info/WHEEL,sha256=yQN5g4mg4AybRjkgi-9yy4iQEFibGQmlz78Pik5Or-A,92
21
+ moteus-0.3.60.dist-info/entry_points.txt,sha256=accRcwir_K8wCf7i3qHb5R6CPh5SiSgd5a1A92ibb9E,56
22
+ moteus-0.3.60.dist-info/top_level.txt,sha256=aZzmI_yecTaDrdSp29pTJuowaSQ9dlIZheQpshGg4YQ,7
23
+ moteus-0.3.60.dist-info/RECORD,,
@@ -1,5 +1,5 @@
1
1
  Wheel-Version: 1.0
2
- Generator: bdist_wheel (0.37.1)
2
+ Generator: bdist_wheel (0.41.2)
3
3
  Root-Is-Purelib: true
4
4
  Tag: py3-none-any
5
5
 
@@ -1,3 +1,2 @@
1
1
  [console_scripts]
2
2
  moteus_tool = moteus.moteus_tool:main
3
-
@@ -1,23 +0,0 @@
1
- moteus/__init__.py,sha256=1Prmih65X7Qz7WY8AUiSwUWXz3Dev8ggQS9xohL75M0,721
2
- moteus/aioserial.py,sha256=lOBFPXManRBMsjMc1zuyw-NRt6CNVMvnj_mQqIZLpyI,1061
3
- moteus/aiostream.py,sha256=SLDXwdBMHIWVTAmeUGG6ke7sntfNVxd9CqapzfniJOo,3678
4
- moteus/calibrate_encoder.py,sha256=kY6mV1WkgCrD9z2YpRoqTTK_BUrRfop4_YJym9AQI-I,12403
5
- moteus/command.py,sha256=IXb0ToAg74fm8FYKPiOdjlzxosqdafLhqADffCvw5OY,1156
6
- moteus/export.py,sha256=dI8QjdqrcI3pi5fKfP25PwLvsIlVJ695x0ta0PVMKx8,1628
7
- moteus/fdcanusb.py,sha256=AMwqdvIRz4X9yA4qz8REuyFBfs3OcLcVqbGX28sEx4s,6729
8
- moteus/moteus.py,sha256=J7nzalhDTUvJq3h1FNjFnYLkrSVnL_IGDU1sw2PNsmU,43869
9
- moteus/moteus_tool.py,sha256=L-7IBs9YHcbd2nc8SPwCEinHvzp09iVb_JeQCUtNM2U,66800
10
- moteus/multiplex.py,sha256=EBOhAE-DHkS_AXtqUl2YEs745evvLMPIMeXQSYxF8zk,10102
11
- moteus/posix_aioserial.py,sha256=3JFiY5p4dtC2ztg6N5SOffnNk9lNcjie02yjD3UlJWo,2971
12
- moteus/pythoncan.py,sha256=lawewmkd9zQuE-Z1LurmpFD2iSWATei65SZb42um_Vg,3309
13
- moteus/reader.py,sha256=jGADQTmONSBMQ25I5AqXELLqil2TEha1KjraPdOsf78,11932
14
- moteus/regression.py,sha256=wpPlxAZ9nC9kfv0oX1K9W2AZNnBLbY8htAJz60SxIb8,1183
15
- moteus/router.py,sha256=k4Tf6hWtHSgzznmdnj4NySe84-y9feYRxGz0yTrJtoc,2043
16
- moteus/transport.py,sha256=3asI2A87eQDImLP74LNLtETaShQRiD9RuCjlxNY6AlE,1003
17
- moteus/version.py,sha256=zpTmrEA7ncnYPk73r5YQJOdYXTB_LBw60As5aQhXRA0,609
18
- moteus/win32_aioserial.py,sha256=SZsnoBWE0Uwo4ZZF8ALB1WNPRY9NiaCOBz6VfvVcnxA,1841
19
- moteus-0.3.58.dist-info/METADATA,sha256=WCPxHMe0doKijEQK9-XAaN5FjXUxTLVdsFn1lRvP4wE,3417
20
- moteus-0.3.58.dist-info/WHEEL,sha256=G16H4A3IeoQmnOrYV4ueZGKSjhipXx8zc8nu9FGlvMA,92
21
- moteus-0.3.58.dist-info/entry_points.txt,sha256=indCsEML1fmtWJU1WiV-d7UmmTaAMhyBLEc1iiKnexQ,57
22
- moteus-0.3.58.dist-info/top_level.txt,sha256=aZzmI_yecTaDrdSp29pTJuowaSQ9dlIZheQpshGg4YQ,7
23
- moteus-0.3.58.dist-info/RECORD,,