diff --git a/CMakeLists.txt b/CMakeLists.txt index ac179ac15..7c68974f1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -143,42 +143,40 @@ target_link_libraries(lie PUBLIC MANIF::manif) ## ESW -if (NOT APPLE) - mrover_add_vendor_header_only_library(moteus deps/mjbots) - mrover_add_header_only_library(can_device src/esw/can_device) - mrover_add_library(motor_library src/esw/motor_library/*.cpp src/esw/motor_library) - target_link_libraries(motor_library PUBLIC can_device moteus) - - if (NetLink_FOUND AND NetLinkRoute_FOUND) - mrover_add_nodelet(can_driver src/esw/can_driver/*.cpp src/esw/can_driver src/esw/can_driver/pch.hpp) - mrover_nodelet_link_libraries(can_driver ${NetLink_LIBRARIES} ${NetLinkRoute_LIBRARIES}) - mrover_nodelet_include_directories(can_driver ${NetLink_INCLUDE_DIRS} ${NetLinkRoute_INCLUDE_DIRS}) - endif () - - macro(mrover_add_esw_bridge_node name sources) - mrover_add_node(${name} ${sources}) - target_link_libraries(${name} PRIVATE can_device motor_library) - endmacro() - - mrover_add_esw_bridge_node(arm_hw_bridge src/esw/arm_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(arm_translator_bridge src/esw/arm_translator_bridge/*.cpp src/esw/arm_translator_bridge/*.hpp) - mrover_add_esw_bridge_node(cache_bridge src/esw/cache_bridge/*.cpp) - mrover_add_esw_bridge_node(drive_bridge src/esw/drive_bridge/*.cpp) - mrover_add_esw_bridge_node(led_hw_bridge src/esw/led_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(led src/esw/led/*.cpp) - mrover_add_esw_bridge_node(mast_gimbal_bridge src/esw/mast_gimbal_bridge/*.cpp) - mrover_add_esw_bridge_node(pdb_bridge src/esw/pdb_bridge/*.cpp) - mrover_add_esw_bridge_node(sa_hw_bridge src/esw/sa_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(sa_translator_bridge src/esw/sa_translator_bridge/*.cpp) - mrover_add_esw_bridge_node(science_bridge src/esw/science_bridge/*.cpp) - mrover_add_esw_bridge_node(brushless_test_bridge src/esw/brushless_test_bridge/*.cpp motor_library) - mrover_add_esw_bridge_node(brushed_test_bridge src/esw/brushed_test_bridge/*.cpp) - mrover_add_esw_bridge_node(test_arm_bridge src/esw/test_arm_bridge/*.cpp) - mrover_add_esw_bridge_node(pdb_test_bridge src/esw/pdb_test_bridge/*.cpp) - mrover_add_esw_bridge_node(arm_position_test_bridge src/esw/arm_position_test_bridge/*.cpp) - # mrover_add_esw_bridge_node(sa_sensor src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino) +mrover_add_vendor_header_only_library(moteus deps/mjbots) +mrover_add_header_only_library(can_device src/esw/can_device) +mrover_add_library(motor_library src/esw/motor_library/*.cpp src/esw/motor_library) +target_link_libraries(motor_library PUBLIC can_device moteus) + +if (NetLink_FOUND AND NetLinkRoute_FOUND) + mrover_add_nodelet(can_driver src/esw/can_driver/*.cpp src/esw/can_driver src/esw/can_driver/pch.hpp) + mrover_nodelet_link_libraries(can_driver ${NetLink_LIBRARIES} ${NetLinkRoute_LIBRARIES}) + mrover_nodelet_include_directories(can_driver ${NetLink_INCLUDE_DIRS} ${NetLinkRoute_INCLUDE_DIRS}) endif () +macro(mrover_add_esw_bridge_node name sources) + mrover_add_node(${name} ${sources}) + target_link_libraries(${name} PRIVATE can_device motor_library) +endmacro() + +mrover_add_esw_bridge_node(arm_hw_bridge src/esw/arm_hw_bridge/*.cpp) +mrover_add_esw_bridge_node(arm_translator_bridge src/esw/arm_translator_bridge/*.cpp src/esw/arm_translator_bridge/*.hpp) +mrover_add_esw_bridge_node(cache_bridge src/esw/cache_bridge/*.cpp) +mrover_add_esw_bridge_node(drive_bridge src/esw/drive_bridge/*.cpp) +mrover_add_esw_bridge_node(led_hw_bridge src/esw/led_hw_bridge/*.cpp) +mrover_add_esw_bridge_node(led src/esw/led/*.cpp) +mrover_add_esw_bridge_node(mast_gimbal_bridge src/esw/mast_gimbal_bridge/*.cpp) +mrover_add_esw_bridge_node(pdb_bridge src/esw/pdb_bridge/*.cpp) +mrover_add_esw_bridge_node(sa_bridge src/esw/sa_bridge/*.cpp) +mrover_add_esw_bridge_node(science_bridge src/esw/science_bridge/*.cpp) +mrover_add_esw_bridge_node(brushless_test_bridge src/esw/brushless_test_bridge/*.cpp) +mrover_add_esw_bridge_node(brushed_test_bridge src/esw/brushed_test_bridge/*.cpp) +mrover_add_esw_bridge_node(science_test_bridge src/esw/science_test_bridge/*.cpp) +mrover_add_esw_bridge_node(test_arm_bridge src/esw/test_arm_bridge/*.cpp) +mrover_add_esw_bridge_node(pdb_test_bridge src/esw/pdb_test_bridge/*.cpp) +# mrover_add_esw_bridge_node(arm_position_test_bridge src/esw/arm_position_test_bridge/*.cpp) +# mrover_add_esw_bridge_node(sa_sensor src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino) + ## Perception mrover_add_library(websocket_server src/esw/websocket_server/*.cpp src/esw/websocket_server) diff --git a/ansible/roles/jetson_build/tasks/main.yml b/ansible/roles/jetson_build/tasks/main.yml index e4258e594..9736001c0 100644 --- a/ansible/roles/jetson_build/tasks/main.yml +++ b/ansible/roles/jetson_build/tasks/main.yml @@ -23,17 +23,17 @@ state: latest name: - zstd # Required to unpack ZED installer - - cuda + - cuda-12-3 - nvidia-jetpack - name: ZED SDK Download get_url: - url: https://download.stereolabs.com/zedsdk/4.0/l4t35.4/jetsons - dest: /tmp/ZED_SDK_Tegra_L4T35.4_v4.0.7.zstd.run + url: https://download.stereolabs.com/zedsdk/4.1/l4t35.4/jetsons + dest: /tmp/ZED_SDK_Tegra_L4T35.4_v4.1.zstd.run mode: 0755 - name: ZED SDK Install # Silent mode prevents any user input prompting - command: /tmp/Downloads/ZED_SDK_Tegra_L4T35.4_v4.0.7.zstd.run -- silent + command: /tmp/Downloads/ZED_SDK_Tegra_L4T35.4_v4.1.zstd.run -- silent args: creates: /usr/local/zed diff --git a/ansible/roles/jetson_services/files/99-usb-serial.rules b/ansible/roles/jetson_services/files/99-usb-serial.rules deleted file mode 100644 index dfdc52298..000000000 --- a/ansible/roles/jetson_services/files/99-usb-serial.rules +++ /dev/null @@ -1,2 +0,0 @@ -SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", SYMLINK+="raman" -SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0043", SYMLINK+="auton_led" diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service deleted file mode 100644 index 7480d3f85..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 0 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5000 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service deleted file mode 100644 index 1032633da..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 1 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5001 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service deleted file mode 100644 index deb6543dc..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 2 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5002 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service deleted file mode 100644 index 06be0fc58..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 3 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5003 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/config/esw.yaml b/config/esw.yaml index 6ef3bc7dd..b29b86477 100644 --- a/config/esw.yaml +++ b/config/esw.yaml @@ -24,22 +24,22 @@ can: bus: 3 id: 0x10 - name: "front_left" - bus: 0 + bus: 2 id: 0x12 - name: "front_right" - bus: 0 + bus: 2 id: 0x11 - name: "middle_left" - bus: 0 + bus: 2 id: 0x14 - name: "middle_right" - bus: 0 + bus: 2 id: 0x13 - name: "back_left" - bus: 0 + bus: 2 id: 0x16 - name: "back_right" - bus: 0 + bus: 2 id: 0x15 - name: "joint_a" bus: 1 @@ -96,35 +96,28 @@ can: brushless_motors: controllers: front_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 front_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 middle_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 middle_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 back_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 back_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -11.0 + max_velocity: 11.0 joint_a: - velocity_multiplier: 1.0 - min_velocity: -100.0 - max_velocity: 100.0 - is_linear: true - rad_to_meters_ratio: 1236.8475 # 5.0 = 5 motor radians -> 1 meter + # 1236.8475 rad/meter, or 196.850393476 rev/meter, and we want a max vel of 40 meter/s. + # gear ratio is currently at 0.005080 revolutions = 1 meter + min_velocity: -0.10 # this means -0.10 meters per second. + max_velocity: 0.10 limit_0_present: true limit_1_present: true limit_0_enabled: true @@ -135,32 +128,33 @@ brushless_motors: limit_1_is_active_high: false limit_0_used_for_readjustment: true limit_1_used_for_readjustment: true - limit_0_readjust_position: 0.0 # radians TODO - limit_1_readjust_position: 494.739 # radians + limit_0_readjust_position: 0.4 + limit_1_readjust_position: 0.0 limit_max_forward_pos: true limit_max_backward_pos: true max_forward_pos: 0.4 max_backward_pos: 0.0 + max_torque: 20.0 joint_c: - velocity_multiplier: -1.0 - min_velocity: -0.6 # gear ratio: 484:1 - max_velocity: 0.6 - min_position: 0.0 - max_position: 3.8 # 220 degrees of motion + min_velocity: -0.08 # in terms of output + max_velocity: 0.08 # max output shaft speed: 5 rpm (for now) + min_position: -0.125 + max_position: 0.30 # 220 degrees of motion is the entire range joint_de_0: - velocity_multiplier: 1.0 - min_velocity: -67.0 - max_velocity: 67.0 + min_velocity: -5.0 + max_velocity: 5.0 + min_position: -10000.0 + max_position: 10000.0 + max_torque: 20.0 joint_de_1: - velocity_multiplier: 1.0 - min_velocity: -67.0 - max_velocity: 67.0 + min_velocity: -5.0 + max_velocity: 5.0 + min_position: -10000.0 + max_position: 10000.0 + max_torque: 20.0 sa_z: - velocity_multiplier: 1.0 - min_velocity: -100.0 - max_velocity: 100.0 - is_linear: true - rad_to_meters_ratio: 157.48 #rad/m + min_velocity: -0.05 + max_velocity: 0.05 limit_0_present: false limit_1_present: false limit_0_enabled: true @@ -173,10 +167,7 @@ brushless_motors: limit_1_used_for_readjustment: true limit_0_readjust_position: 0.0 # radians TODO limit_1_readjust_position: 0.0 # radians TODO - max_torque: 0.5 -joint_de: - pitch_offset: 0.0 - roll_offset: 0.0 + max_torque: 30.0 brushed_motors: controllers: @@ -221,16 +212,15 @@ brushed_motors: # max_backward_pos: 0.0 # calibration_throttle: 5.0 joint_b: - velocity_multiplier: 1.0 + is_inverted: False gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: true limit_0_enabled: true limit_0_is_active_high: false limit_0_limits_fwd: false - limit_0_used_for_readjustment: true + limit_0_used_for_readjustment: false abs_present: true abs_is_fwd_polarity: true - limit_0_readjust_position: -0.7853981633974483 # radians abs_ratio: 1.0 # encoder ratio compared to motor abs_offset: 0.0 # 0 for joint position corresponds to this radians reading by absolute encoder driver_voltage: 12.0 # used to calculate max pwm @@ -242,7 +232,6 @@ brushed_motors: max_velocity: 1.0 calibration_throttle: 0.5 # throttle during calibration allen_key: - velocity_multiplier: 1.0 gear_ratio: 30.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: true limit_1_present: true @@ -261,9 +250,8 @@ brushed_motors: quad_ratio: 1.0 # encoder ratio compared to motor driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm - calibration_throttle: 0.5 # throttle during calibration + calibration_throttle: 0.9 # throttle during calibration, does not move unless close to max voltage gripper: - velocity_multiplier: 1.0 gear_ratio: 47.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint quad_present: false quad_is_fwd_polarity: true @@ -274,19 +262,15 @@ brushed_motors: motor_max_voltage: 12.0 # used to calculate max pwm calibration_throttle: 0.5 # throttle during calibration mast_gimbal_y: - velocity_multiplier: 1.0 gear_ratio: 1000.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm mast_gimbal_z: - velocity_multiplier: 1.0 gear_ratio: 1000.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm sa_x: - velocity_multiplier: 1.0 gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter limit_0_present: false limit_1_present: false @@ -314,12 +298,10 @@ brushed_motors: max_velocity: 1.0 calibration_throttle: 0.5 # throttle during calibration sa_y: - velocity_multiplier: -1.0 gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter - limit_0_present: false - limit_1_present: false + limit_0_present: true + limit_1_present: true limit_0_enabled: true limit_1_enabled: true limit_0_is_active_high: false @@ -340,7 +322,6 @@ brushed_motors: calibration_throttle: 0.5 # throttle during calibration sampler: gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter limit_0_present: false limit_1_present: false @@ -361,7 +342,6 @@ brushed_motors: motor_max_voltage: 6.0 # used to calculate max pwm calibration_throttle: 0.5 # throttle during calibration sensor_actuator: - velocity_multiplier: 1.0 gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: false limit_1_present: false @@ -378,7 +358,6 @@ brushed_motors: driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 6.0 # used to calculate max pwm cache: - velocity_multiplier: 1.0 gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: false limit_1_present: false @@ -540,24 +519,25 @@ motors_group: - "mast_gimbal_z" cache: - "cache_motor" - sa_hw: + sa: - "sa_x" - "sa_y" - "sa_z" - "sampler" - "sensor_actuator" - drive: + drive_left: - "front_left" - - "front_right" - "middle_left" - - "middle_right" - "back_left" + drive_right: + - "front_right" + - "middle_right" - "back_right" motors: controllers: joint_a: - type: "brushless" + type: "brushless_linear" joint_b: type: "brushed" joint_c: diff --git a/config/moteus/de0/reads_position.config b/config/moteus/de0/reads_position.config deleted file mode 100644 index 1c9a1d255..000000000 --- a/config/moteus/de0/reads_position.config +++ /dev/null @@ -1,1283 +0,0 @@ -le.11 0.000000 -motor_position.sources.0.compensation_table.12 0.000000 -motor_position.sources.0.compensation_table.13 0.000000 -motor_position.sources.0.compensation_table.14 0.000000 -motor_position.sources.0.compensation_table.15 0.000000 -motor_position.sources.0.compensation_table.16 0.000000 -motor_position.sources.0.compensation_table.17 0.000000 -motor_position.sources.0.compensation_table.18 0.000000 -motor_position.sources.0.compensation_table.19 0.000000 -motor_position.sources.0.compensation_table.20 0.000000 -motor_position.sources.0.compensation_table.21 0.000000 -motor_position.sources.0.compensation_table.22 0.000000 -motor_position.sources.0.compensation_table.23 0.000000 -motor_position.sources.0.compensation_table.24 0.000000 -motor_position.sources.0.compensation_table.25 0.000000 -motor_position.sources.0.compensation_table.26 0.000000 -motor_position.sources.0.compensation_table.27 0.000000 -motor_position.sources.0.compensation_table.28 0.000000 -motor_position.sources.0.compensation_table.29 0.000000 -motor_position.sources.0.compensation_table.30 0.000000 -motor_position.sources.0.compensation_table.31 0.000000 -motor_position.sources.1.aux_number 1 -motor_position.sources.1.type 0 -motor_position.sources.1.i2c_device 0 -motor_position.sources.1.incremental_index -1 -motor_position.sources.1.cpr 16384 -motor_position.sources.1.offset 0.000000 -motor_position.sources.1.sign 1 -motor_position.sources.1.debug_override -1 -motor_position.sources.1.reference 0 -motor_position.sources.1.pll_filter_hz 400.000000 -motor_position.sources.1.compensation_table.0 0.000000 -motor_position.sources.1.compensation_table.1 0.000000 -motor_position.sources.1.compensation_table.2 0.000000 -motor_position.sources.1.compensation_table.3 0.000000 -motor_position.sources.1.compensation_table.4 0.000000 -motor_position.sources.1.compensation_table.5 0.000000 -motor_position.sources.1.compensation_table.6 0.000000 -motor_position.sources.1.compensation_table.7 0.000000 -motor_position.sources.1.compensation_table.8 0.000000 -motor_position.sources.1.compensation_table.9 0.000000 -motor_position.sources.1.compensation_table.10 0.000000 -motor_position.sources.1.compensation_table.11 0.000000 -motor_position.sources.1.compensation_table.12 0.000000 -motor_position.sources.1.compensation_table.13 0.000000 -motor_position.sources.1.compensation_table.14 0.000000 -motor_position.sources.1.compensation_table.15 0.000000 -motor_position.sources.1.compensation_table.16 0.000000 -motor_position.sources.1.compensation_table.17 0.000000 -motor_position.sources.1.compensation_table.18 0.000000 -motor_position.sources.1.compensation_table.19 0.000000 -motor_position.sources.1.compensation_table.20 0.000000 -motor_position.sources.1.compensation_table.21 0.000000 -motor_position.sources.1.compensation_table.22 0.000000 -motor_position.sources.1.compensation_table.23 0.000000 -motor_position.sources.1.compensation_table.24 0.000000 -motor_position.sources.1.compensation_table.25 0.000000 -motor_position.sources.1.compensation_table.26 0.000000 -motor_position.sources.1.compensation_table.27 0.000000 -motor_position.sources.1.compensation_table.28 0.000000 -motor_position.sources.1.compensation_table.29 0.000000 -motor_position.sources.1.compensation_table.30 0.000000 -motor_position.sources.1.compensation_table.31 0.000000 -motor_position.sources.2.aux_number 1 -motor_position.sources.2.type 0 -motor_position.sources.2.i2c_device 0 -motor_position.sources.2.incremental_index -1 -motor_position.sources.2.cpr 16384 -motor_position.sources.2.offset 0.000000 -motor_position.sources.2.sign 1 -motor_position.sources.2.debug_override -1 -motor_position.sources.2.reference 0 -motor_position.sources.2.pll_filter_hz 400.000000 -motor_position.sources.2.compensation_table.0 0.000000 -motor_position.sources.2.compensation_table.1 0.000000 -motor_position.sources.2.compensation_table.2 0.000000 -motor_position.sources.2.compensation_table.3 0.000000 -motor_position.sources.2.compensation_table.4 0.000000 -motor_position.sources.2.compensation_table.5 0.000000 -motor_position.sources.2.compensation_table.6 0.000000 -motor_position.sources.2.compensation_table.7 0.000000 -motor_position.sources.2.compensation_table.8 0.000000 -motor_position.sources.2.compensation_table.9 0.000000 -motor_position.sources.2.compensation_table.10 0.000000 -motor_position.sources.2.compensation_table.11 0.000000 -motor_position.sources.2.compensation_table.12 0.000000 -motor_position.sources.2.compensation_table.13 0.000000 -motor_position.sources.2.compensation_table.14 0.000000 -motor_position.sources.2.compensation_table.15 0.000000 -motor_position.sources.2.compensation_table.16 0.000000 -motor_position.sources.2.compensation_table.17 0.000000 -motor_position.sources.2.compensation_table.18 0.000000 -motor_position.sources.2.compensation_table.19 0.000000 -motor_position.sources.2.compensation_table.20 0.000000 -motor_position.sources.2.compensation_table.21 0.000000 -motor_position.sources.2.compensation_table.22 0.000000 -motor_position.sources.2.compensation_table.23 0.000000 -motor_position.sources.2.compensation_table.24 0.000000 -motor_position.sources.2.compensation_table.25 0.000000 -motor_position.sources.2.compensation_table.26 0.000000 -motor_position.sources.2.compensation_table.27 0.000000 -motor_position.sources.2.compensation_table.28 0.000000 -motor_position.sources.2.compensation_table.29 0.000000 -motor_position.sources.2.compensation_table.30 0.000000 -motor_position.sources.2.compensation_table.31 0.000000 -motor_position.commutation_source 0 -motor_position.output.source 0 -motor_position.output.offset 0.000000 -motor_position.output.sign 1 -motor_position.output.reference_source -1 -motor_position.rotor_to_output_ratio 1.000000 -motor.poles 16 -motor.phase_invert 0 -motor.resistance_ohm 4.243308 -motor.v_per_hz 0.594227 -motor.offset.0 0.000000 -motor.offset.1 0.000000 -motor.offset.2 0.000000 -motor.offset.3 0.000000 -motor.offset.4 0.000000 -motor.offset.5 0.000000 -motor.offset.6 0.000000 -motor.offset.7 0.000000 -motor.offset.8 0.000000 -motor.offset.9 0.000000 -motor.offset.10 0.000000 -motor.offset.11 0.000000 -motor.offset.12 0.000000 -motor.offset.13 0.000000 -motor.offset.14 0.000000 -motor.offset.15 0.000000 -motor.offset.16 0.000000 -motor.offset.17 0.000000 -motor.offset.18 0.000000 -motor.offset.19 0.000000 -motor.offset.20 0.000000 -motor.offset.21 0.000000 -motor.offset.22 0.000000 -motor.offset.23 0.000000 -motor.offset.24 0.000000 -motor.offset.25 0.000000 -motor.offset.26 0.000000 -motor.offset.27 0.000000 -motor.offset.28 0.000000 -motor.offset.29 0.000000 -motor.offset.30 0.000000 -motor.offset.31 0.000000 -motor.offset.32 0.000000 -motor.offset.33 0.000000 -motor.offset.34 0.000000 -motor.offset.35 0.000000 -motor.offset.36 0.000000 -motor.offset.37 0.000000 -motor.offset.38 0.000000 -motor.offset.39 0.000000 -motor.offset.40 0.000000 -motor.offset.41 0.000000 -motor.offset.42 0.000000 -motor.offset.43 0.000000 -motor.offset.44 0.000000 -motor.offset.45 0.000000 -motor.offset.46 0.000000 -motor.offset.47 0.000000 -motor.offset.48 0.000000 -motor.offset.49 0.000000 -motor.offset.50 0.000000 -motor.offset.51 0.000000 -motor.offset.52 0.000000 -motor.offset.53 0.000000 -motor.offset.54 0.000000 -motor.offset.55 0.000000 -motor.offset.56 0.000000 -motor.offset.57 0.000000 -motor.offset.58 0.000000 -motor.offset.59 0.000000 -motor.offset.60 0.000000 -motor.offset.61 0.000000 -motor.offset.62 0.000000 -motor.offset.63 0.000000 -motor.rotation_current_cutoff_A 10000.000000 -motor.rotation_current_scale 0.050000 -motor.rotation_torque_scale 14.700000 -motor.cogging_dq_scale 0.000000 -motor.cogging_dq_comp.0 0 -motor.cogging_dq_comp.1 0 -motor.cogging_dq_comp.2 0 -motor.cogging_dq_comp.3 0 -motor.cogging_dq_comp.4 0 -motor.cogging_dq_comp.5 0 -motor.cogging_dq_comp.6 0 -motor.cogging_dq_comp.7 0 -motor.cogging_dq_comp.8 0 -motor.cogging_dq_comp.9 0 -motor.cogging_dq_comp.10 0 -motor.cogging_dq_comp.11 0 -motor.cogging_dq_comp.12 0 -motor.cogging_dq_comp.13 0 -motor.cogging_dq_comp.14 0 -motor.cogging_dq_comp.15 0 -motor.cogging_dq_comp.16 0 -motor.cogging_dq_comp.17 0 -motor.cogging_dq_comp.18 0 -motor.cogging_dq_comp.19 0 -motor.cogging_dq_comp.20 0 -motor.cogging_dq_comp.21 0 -motor.cogging_dq_comp.22 0 -motor.cogging_dq_comp.23 0 -motor.cogging_dq_comp.24 0 -motor.cogging_dq_comp.25 0 -motor.cogging_dq_comp.26 0 -motor.cogging_dq_comp.27 0 -motor.cogging_dq_comp.28 0 -motor.cogging_dq_comp.29 0 -motor.cogging_dq_comp.30 0 -motor.cogging_dq_comp.31 0 -motor.cogging_dq_comp.32 0 -motor.cogging_dq_comp.33 0 -motor.cogging_dq_comp.34 0 -motor.cogging_dq_comp.35 0 -motor.cogging_dq_comp.36 0 -motor.cogging_dq_comp.37 0 -motor.cogging_dq_comp.38 0 -motor.cogging_dq_comp.39 0 -motor.cogging_dq_comp.40 0 -motor.cogging_dq_comp.41 0 -motor.cogging_dq_comp.42 0 -motor.cogging_dq_comp.43 0 -motor.cogging_dq_comp.44 0 -motor.cogging_dq_comp.45 0 -motor.cogging_dq_comp.46 0 -motor.cogging_dq_comp.47 0 -motor.cogging_dq_comp.48 0 -motor.cogging_dq_comp.49 0 -motor.cogging_dq_comp.50 0 -motor.cogging_dq_comp.51 0 -motor.cogging_dq_comp.52 0 -motor.cogging_dq_comp.53 0 -motor.cogging_dq_comp.54 0 -motor.cogging_dq_comp.55 0 -motor.cogging_dq_comp.56 0 -motor.cogging_dq_comp.57 0 -motor.cogging_dq_comp.58 0 -motor.cogging_dq_comp.59 0 -motor.cogging_dq_comp.60 0 -motor.cogging_dq_comp.61 0 -motor.cogging_dq_comp.62 0 -motor.cogging_dq_comp.63 0 -motor.cogging_dq_comp.64 0 -motor.cogging_dq_comp.65 0 -motor.cogging_dq_comp.66 0 -motor.cogging_dq_comp.67 0 -motor.cogging_dq_comp.68 0 -motor.cogging_dq_comp.69 0 -motor.cogging_dq_comp.70 0 -motor.cogging_dq_comp.71 0 -motor.cogging_dq_comp.72 0 -motor.cogging_dq_comp.73 0 -motor.cogging_dq_comp.74 0 -motor.cogging_dq_comp.75 0 -motor.cogging_dq_comp.76 0 -motor.cogging_dq_comp.77 0 -motor.cogging_dq_comp.78 0 -motor.cogging_dq_comp.79 0 -motor.cogging_dq_comp.80 0 -motor.cogging_dq_comp.81 0 -motor.cogging_dq_comp.82 0 -motor.cogging_dq_comp.83 0 -motor.cogging_dq_comp.84 0 -motor.cogging_dq_comp.85 0 -motor.cogging_dq_comp.86 0 -motor.cogging_dq_comp.87 0 -motor.cogging_dq_comp.88 0 -motor.cogging_dq_comp.89 0 -motor.cogging_dq_comp.90 0 -motor.cogging_dq_comp.91 0 -motor.cogging_dq_comp.92 0 -motor.cogging_dq_comp.93 0 -motor.cogging_dq_comp.94 0 -motor.cogging_dq_comp.95 0 -motor.cogging_dq_comp.96 0 -motor.cogging_dq_comp.97 0 -motor.cogging_dq_comp.98 0 -motor.cogging_dq_comp.99 0 -motor.cogging_dq_comp.100 0 -motor.cogging_dq_comp.101 0 -motor.cogging_dq_comp.102 0 -motor.cogging_dq_comp.103 0 -motor.cogging_dq_comp.104 0 -motor.cogging_dq_comp.105 0 -motor.cogging_dq_comp.106 0 -motor.cogging_dq_comp.107 0 -motor.cogging_dq_comp.108 0 -motor.cogging_dq_comp.109 0 -motor.cogging_dq_comp.110 0 -motor.cogging_dq_comp.111 0 -motor.cogging_dq_comp.112 0 -motor.cogging_dq_comp.113 0 -motor.cogging_dq_comp.114 0 -motor.cogging_dq_comp.115 0 -motor.cogging_dq_comp.116 0 -motor.cogging_dq_comp.117 0 -motor.cogging_dq_comp.118 0 -motor.cogging_dq_comp.119 0 -motor.cogging_dq_comp.120 0 -motor.cogging_dq_comp.121 0 -motor.cogging_dq_comp.122 0 -motor.cogging_dq_comp.123 0 -motor.cogging_dq_comp.124 0 -motor.cogging_dq_comp.125 0 -motor.cogging_dq_comp.126 0 -motor.cogging_dq_comp.127 0 -motor.cogging_dq_comp.128 0 -motor.cogging_dq_comp.129 0 -motor.cogging_dq_comp.130 0 -motor.cogging_dq_comp.131 0 -motor.cogging_dq_comp.132 0 -motor.cogging_dq_comp.133 0 -motor.cogging_dq_comp.134 0 -motor.cogging_dq_comp.135 0 -motor.cogging_dq_comp.136 0 -motor.cogging_dq_comp.137 0 -motor.cogging_dq_comp.138 0 -motor.cogging_dq_comp.139 0 -motor.cogging_dq_comp.140 0 -motor.cogging_dq_comp.141 0 -motor.cogging_dq_comp.142 0 -motor.cogging_dq_comp.143 0 -motor.cogging_dq_comp.144 0 -motor.cogging_dq_comp.145 0 -motor.cogging_dq_comp.146 0 -motor.cogging_dq_comp.147 0 -motor.cogging_dq_comp.148 0 -motor.cogging_dq_comp.149 0 -motor.cogging_dq_comp.150 0 -motor.cogging_dq_comp.151 0 -motor.cogging_dq_comp.152 0 -motor.cogging_dq_comp.153 0 -motor.cogging_dq_comp.154 0 -motor.cogging_dq_comp.155 0 -motor.cogging_dq_comp.156 0 -motor.cogging_dq_comp.157 0 -motor.cogging_dq_comp.158 0 -motor.cogging_dq_comp.159 0 -motor.cogging_dq_comp.160 0 -motor.cogging_dq_comp.161 0 -motor.cogging_dq_comp.162 0 -motor.cogging_dq_comp.163 0 -motor.cogging_dq_comp.164 0 -motor.cogging_dq_comp.165 0 -motor.cogging_dq_comp.166 0 -motor.cogging_dq_comp.167 0 -motor.cogging_dq_comp.168 0 -motor.cogging_dq_comp.169 0 -motor.cogging_dq_comp.170 0 -motor.cogging_dq_comp.171 0 -motor.cogging_dq_comp.172 0 -motor.cogging_dq_comp.173 0 -motor.cogging_dq_comp.174 0 -motor.cogging_dq_comp.175 0 -motor.cogging_dq_comp.176 0 -motor.cogging_dq_comp.177 0 -motor.cogging_dq_comp.178 0 -motor.cogging_dq_comp.179 0 -motor.cogging_dq_comp.180 0 -motor.cogging_dq_comp.181 0 -motor.cogging_dq_comp.182 0 -motor.cogging_dq_comp.183 0 -motor.cogging_dq_comp.184 0 -motor.cogging_dq_comp.185 0 -motor.cogging_dq_comp.186 0 -motor.cogging_dq_comp.187 0 -motor.cogging_dq_comp.188 0 -motor.cogging_dq_comp.189 0 -motor.cogging_dq_comp.190 0 -motor.cogging_dq_comp.191 0 -motor.cogging_dq_comp.192 0 -motor.cogging_dq_comp.193 0 -motor.cogging_dq_comp.194 0 -motor.cogging_dq_comp.195 0 -motor.cogging_dq_comp.196 0 -motor.cogging_dq_comp.197 0 -motor.cogging_dq_comp.198 0 -motor.cogging_dq_comp.199 0 -motor.cogging_dq_comp.200 0 -motor.cogging_dq_comp.201 0 -motor.cogging_dq_comp.202 0 -motor.cogging_dq_comp.203 0 -motor.cogging_dq_comp.204 0 -motor.cogging_dq_comp.205 0 -motor.cogging_dq_comp.206 0 -motor.cogging_dq_comp.207 0 -motor.cogging_dq_comp.208 0 -motor.cogging_dq_comp.209 0 -motor.cogging_dq_comp.210 0 -motor.cogging_dq_comp.211 0 -motor.cogging_dq_comp.212 0 -motor.cogging_dq_comp.213 0 -motor.cogging_dq_comp.214 0 -motor.cogging_dq_comp.215 0 -motor.cogging_dq_comp.216 0 -motor.cogging_dq_comp.217 0 -motor.cogging_dq_comp.218 0 -motor.cogging_dq_comp.219 0 -motor.cogging_dq_comp.220 0 -motor.cogging_dq_comp.221 0 -motor.cogging_dq_comp.222 0 -motor.cogging_dq_comp.223 0 -motor.cogging_dq_comp.224 0 -motor.cogging_dq_comp.225 0 -motor.cogging_dq_comp.226 0 -motor.cogging_dq_comp.227 0 -motor.cogging_dq_comp.228 0 -motor.cogging_dq_comp.229 0 -motor.cogging_dq_comp.230 0 -motor.cogging_dq_comp.231 0 -motor.cogging_dq_comp.232 0 -motor.cogging_dq_comp.233 0 -motor.cogging_dq_comp.234 0 -motor.cogging_dq_comp.235 0 -motor.cogging_dq_comp.236 0 -motor.cogging_dq_comp.237 0 -motor.cogging_dq_comp.238 0 -motor.cogging_dq_comp.239 0 -motor.cogging_dq_comp.240 0 -motor.cogging_dq_comp.241 0 -motor.cogging_dq_comp.242 0 -motor.cogging_dq_comp.243 0 -motor.cogging_dq_comp.244 0 -motor.cogging_dq_comp.245 0 -motor.cogging_dq_comp.246 0 -motor.cogging_dq_comp.247 0 -motor.cogging_dq_comp.248 0 -motor.cogging_dq_comp.249 0 -motor.cogging_dq_comp.250 0 -motor.cogging_dq_comp.251 0 -motor.cogging_dq_comp.252 0 -motor.cogging_dq_comp.253 0 -motor.cogging_dq_comp.254 0 -motor.cogging_dq_comp.255 0 -motor.cogging_dq_comp.256 0 -motor.cogging_dq_comp.257 0 -motor.cogging_dq_comp.258 0 -motor.cogging_dq_comp.259 0 -motor.cogging_dq_comp.260 0 -motor.cogging_dq_comp.261 0 -motor.cogging_dq_comp.262 0 -motor.cogging_dq_comp.263 0 -motor.cogging_dq_comp.264 0 -motor.cogging_dq_comp.265 0 -motor.cogging_dq_comp.266 0 -motor.cogging_dq_comp.267 0 -motor.cogging_dq_comp.268 0 -motor.cogging_dq_comp.269 0 -motor.cogging_dq_comp.270 0 -motor.cogging_dq_comp.271 0 -motor.cogging_dq_comp.272 0 -motor.cogging_dq_comp.273 0 -motor.cogging_dq_comp.274 0 -motor.cogging_dq_comp.275 0 -motor.cogging_dq_comp.276 0 -motor.cogging_dq_comp.277 0 -motor.cogging_dq_comp.278 0 -motor.cogging_dq_comp.279 0 -motor.cogging_dq_comp.280 0 -motor.cogging_dq_comp.281 0 -motor.cogging_dq_comp.282 0 -motor.cogging_dq_comp.283 0 -motor.cogging_dq_comp.284 0 -motor.cogging_dq_comp.285 0 -motor.cogging_dq_comp.286 0 -motor.cogging_dq_comp.287 0 -motor.cogging_dq_comp.288 0 -motor.cogging_dq_comp.289 0 -motor.cogging_dq_comp.290 0 -motor.cogging_dq_comp.291 0 -motor.cogging_dq_comp.292 0 -motor.cogging_dq_comp.293 0 -motor.cogging_dq_comp.294 0 -motor.cogging_dq_comp.295 0 -motor.cogging_dq_comp.296 0 -motor.cogging_dq_comp.297 0 -motor.cogging_dq_comp.298 0 -motor.cogging_dq_comp.299 0 -motor.cogging_dq_comp.300 0 -motor.cogging_dq_comp.301 0 -motor.cogging_dq_comp.302 0 -motor.cogging_dq_comp.303 0 -motor.cogging_dq_comp.304 0 -motor.cogging_dq_comp.305 0 -motor.cogging_dq_comp.306 0 -motor.cogging_dq_comp.307 0 -motor.cogging_dq_comp.308 0 -motor.cogging_dq_comp.309 0 -motor.cogging_dq_comp.310 0 -motor.cogging_dq_comp.311 0 -motor.cogging_dq_comp.312 0 -motor.cogging_dq_comp.313 0 -motor.cogging_dq_comp.314 0 -motor.cogging_dq_comp.315 0 -motor.cogging_dq_comp.316 0 -motor.cogging_dq_comp.317 0 -motor.cogging_dq_comp.318 0 -motor.cogging_dq_comp.319 0 -motor.cogging_dq_comp.320 0 -motor.cogging_dq_comp.321 0 -motor.cogging_dq_comp.322 0 -motor.cogging_dq_comp.323 0 -motor.cogging_dq_comp.324 0 -motor.cogging_dq_comp.325 0 -motor.cogging_dq_comp.326 0 -motor.cogging_dq_comp.327 0 -motor.cogging_dq_comp.328 0 -motor.cogging_dq_comp.329 0 -motor.cogging_dq_comp.330 0 -motor.cogging_dq_comp.331 0 -motor.cogging_dq_comp.332 0 -motor.cogging_dq_comp.333 0 -motor.cogging_dq_comp.334 0 -motor.cogging_dq_comp.335 0 -motor.cogging_dq_comp.336 0 -motor.cogging_dq_comp.337 0 -motor.cogging_dq_comp.338 0 -motor.cogging_dq_comp.339 0 -motor.cogging_dq_comp.340 0 -motor.cogging_dq_comp.341 0 -motor.cogging_dq_comp.342 0 -motor.cogging_dq_comp.343 0 -motor.cogging_dq_comp.344 0 -motor.cogging_dq_comp.345 0 -motor.cogging_dq_comp.346 0 -motor.cogging_dq_comp.347 0 -motor.cogging_dq_comp.348 0 -motor.cogging_dq_comp.349 0 -motor.cogging_dq_comp.350 0 -motor.cogging_dq_comp.351 0 -motor.cogging_dq_comp.352 0 -motor.cogging_dq_comp.353 0 -motor.cogging_dq_comp.354 0 -motor.cogging_dq_comp.355 0 -motor.cogging_dq_comp.356 0 -motor.cogging_dq_comp.357 0 -motor.cogging_dq_comp.358 0 -motor.cogging_dq_comp.359 0 -motor.cogging_dq_comp.360 0 -motor.cogging_dq_comp.361 0 -motor.cogging_dq_comp.362 0 -motor.cogging_dq_comp.363 0 -motor.cogging_dq_comp.364 0 -motor.cogging_dq_comp.365 0 -motor.cogging_dq_comp.366 0 -motor.cogging_dq_comp.367 0 -motor.cogging_dq_comp.368 0 -motor.cogging_dq_comp.369 0 -motor.cogging_dq_comp.370 0 -motor.cogging_dq_comp.371 0 -motor.cogging_dq_comp.372 0 -motor.cogging_dq_comp.373 0 -motor.cogging_dq_comp.374 0 -motor.cogging_dq_comp.375 0 -motor.cogging_dq_comp.376 0 -motor.cogging_dq_comp.377 0 -motor.cogging_dq_comp.378 0 -motor.cogging_dq_comp.379 0 -motor.cogging_dq_comp.380 0 -motor.cogging_dq_comp.381 0 -motor.cogging_dq_comp.382 0 -motor.cogging_dq_comp.383 0 -motor.cogging_dq_comp.384 0 -motor.cogging_dq_comp.385 0 -motor.cogging_dq_comp.386 0 -motor.cogging_dq_comp.387 0 -motor.cogging_dq_comp.388 0 -motor.cogging_dq_comp.389 0 -motor.cogging_dq_comp.390 0 -motor.cogging_dq_comp.391 0 -motor.cogging_dq_comp.392 0 -motor.cogging_dq_comp.393 0 -motor.cogging_dq_comp.394 0 -motor.cogging_dq_comp.395 0 -motor.cogging_dq_comp.396 0 -motor.cogging_dq_comp.397 0 -motor.cogging_dq_comp.398 0 -motor.cogging_dq_comp.399 0 -motor.cogging_dq_comp.400 0 -motor.cogging_dq_comp.401 0 -motor.cogging_dq_comp.402 0 -motor.cogging_dq_comp.403 0 -motor.cogging_dq_comp.404 0 -motor.cogging_dq_comp.405 0 -motor.cogging_dq_comp.406 0 -motor.cogging_dq_comp.407 0 -motor.cogging_dq_comp.408 0 -motor.cogging_dq_comp.409 0 -motor.cogging_dq_comp.410 0 -motor.cogging_dq_comp.411 0 -motor.cogging_dq_comp.412 0 -motor.cogging_dq_comp.413 0 -motor.cogging_dq_comp.414 0 -motor.cogging_dq_comp.415 0 -motor.cogging_dq_comp.416 0 -motor.cogging_dq_comp.417 0 -motor.cogging_dq_comp.418 0 -motor.cogging_dq_comp.419 0 -motor.cogging_dq_comp.420 0 -motor.cogging_dq_comp.421 0 -motor.cogging_dq_comp.422 0 -motor.cogging_dq_comp.423 0 -motor.cogging_dq_comp.424 0 -motor.cogging_dq_comp.425 0 -motor.cogging_dq_comp.426 0 -motor.cogging_dq_comp.427 0 -motor.cogging_dq_comp.428 0 -motor.cogging_dq_comp.429 0 -motor.cogging_dq_comp.430 0 -motor.cogging_dq_comp.431 0 -motor.cogging_dq_comp.432 0 -motor.cogging_dq_comp.433 0 -motor.cogging_dq_comp.434 0 -motor.cogging_dq_comp.435 0 -motor.cogging_dq_comp.436 0 -motor.cogging_dq_comp.437 0 -motor.cogging_dq_comp.438 0 -motor.cogging_dq_comp.439 0 -motor.cogging_dq_comp.440 0 -motor.cogging_dq_comp.441 0 -motor.cogging_dq_comp.442 0 -motor.cogging_dq_comp.443 0 -motor.cogging_dq_comp.444 0 -motor.cogging_dq_comp.445 0 -motor.cogging_dq_comp.446 0 -motor.cogging_dq_comp.447 0 -motor.cogging_dq_comp.448 0 -motor.cogging_dq_comp.449 0 -motor.cogging_dq_comp.450 0 -motor.cogging_dq_comp.451 0 -motor.cogging_dq_comp.452 0 -motor.cogging_dq_comp.453 0 -motor.cogging_dq_comp.454 0 -motor.cogging_dq_comp.455 0 -motor.cogging_dq_comp.456 0 -motor.cogging_dq_comp.457 0 -motor.cogging_dq_comp.458 0 -motor.cogging_dq_comp.459 0 -motor.cogging_dq_comp.460 0 -motor.cogging_dq_comp.461 0 -motor.cogging_dq_comp.462 0 -motor.cogging_dq_comp.463 0 -motor.cogging_dq_comp.464 0 -motor.cogging_dq_comp.465 0 -motor.cogging_dq_comp.466 0 -motor.cogging_dq_comp.467 0 -motor.cogging_dq_comp.468 0 -motor.cogging_dq_comp.469 0 -motor.cogging_dq_comp.470 0 -motor.cogging_dq_comp.471 0 -motor.cogging_dq_comp.472 0 -motor.cogging_dq_comp.473 0 -motor.cogging_dq_comp.474 0 -motor.cogging_dq_comp.475 0 -motor.cogging_dq_comp.476 0 -motor.cogging_dq_comp.477 0 -motor.cogging_dq_comp.478 0 -motor.cogging_dq_comp.479 0 -motor.cogging_dq_comp.480 0 -motor.cogging_dq_comp.481 0 -motor.cogging_dq_comp.482 0 -motor.cogging_dq_comp.483 0 -motor.cogging_dq_comp.484 0 -motor.cogging_dq_comp.485 0 -motor.cogging_dq_comp.486 0 -motor.cogging_dq_comp.487 0 -motor.cogging_dq_comp.488 0 -motor.cogging_dq_comp.489 0 -motor.cogging_dq_comp.490 0 -motor.cogging_dq_comp.491 0 -motor.cogging_dq_comp.492 0 -motor.cogging_dq_comp.493 0 -motor.cogging_dq_comp.494 0 -motor.cogging_dq_comp.495 0 -motor.cogging_dq_comp.496 0 -motor.cogging_dq_comp.497 0 -motor.cogging_dq_comp.498 0 -motor.cogging_dq_comp.499 0 -motor.cogging_dq_comp.500 0 -motor.cogging_dq_comp.501 0 -motor.cogging_dq_comp.502 0 -motor.cogging_dq_comp.503 0 -motor.cogging_dq_comp.504 0 -motor.cogging_dq_comp.505 0 -motor.cogging_dq_comp.506 0 -motor.cogging_dq_comp.507 0 -motor.cogging_dq_comp.508 0 -motor.cogging_dq_comp.509 0 -motor.cogging_dq_comp.510 0 -motor.cogging_dq_comp.511 0 -motor.cogging_dq_comp.512 0 -motor.cogging_dq_comp.513 0 -motor.cogging_dq_comp.514 0 -motor.cogging_dq_comp.515 0 -motor.cogging_dq_comp.516 0 -motor.cogging_dq_comp.517 0 -motor.cogging_dq_comp.518 0 -motor.cogging_dq_comp.519 0 -motor.cogging_dq_comp.520 0 -motor.cogging_dq_comp.521 0 -motor.cogging_dq_comp.522 0 -motor.cogging_dq_comp.523 0 -motor.cogging_dq_comp.524 0 -motor.cogging_dq_comp.525 0 -motor.cogging_dq_comp.526 0 -motor.cogging_dq_comp.527 0 -motor.cogging_dq_comp.528 0 -motor.cogging_dq_comp.529 0 -motor.cogging_dq_comp.530 0 -motor.cogging_dq_comp.531 0 -motor.cogging_dq_comp.532 0 -motor.cogging_dq_comp.533 0 -motor.cogging_dq_comp.534 0 -motor.cogging_dq_comp.535 0 -motor.cogging_dq_comp.536 0 -motor.cogging_dq_comp.537 0 -motor.cogging_dq_comp.538 0 -motor.cogging_dq_comp.539 0 -motor.cogging_dq_comp.540 0 -motor.cogging_dq_comp.541 0 -motor.cogging_dq_comp.542 0 -motor.cogging_dq_comp.543 0 -motor.cogging_dq_comp.544 0 -motor.cogging_dq_comp.545 0 -motor.cogging_dq_comp.546 0 -motor.cogging_dq_comp.547 0 -motor.cogging_dq_comp.548 0 -motor.cogging_dq_comp.549 0 -motor.cogging_dq_comp.550 0 -motor.cogging_dq_comp.551 0 -motor.cogging_dq_comp.552 0 -motor.cogging_dq_comp.553 0 -motor.cogging_dq_comp.554 0 -motor.cogging_dq_comp.555 0 -motor.cogging_dq_comp.556 0 -motor.cogging_dq_comp.557 0 -motor.cogging_dq_comp.558 0 -motor.cogging_dq_comp.559 0 -motor.cogging_dq_comp.560 0 -motor.cogging_dq_comp.561 0 -motor.cogging_dq_comp.562 0 -motor.cogging_dq_comp.563 0 -motor.cogging_dq_comp.564 0 -motor.cogging_dq_comp.565 0 -motor.cogging_dq_comp.566 0 -motor.cogging_dq_comp.567 0 -motor.cogging_dq_comp.568 0 -motor.cogging_dq_comp.569 0 -motor.cogging_dq_comp.570 0 -motor.cogging_dq_comp.571 0 -motor.cogging_dq_comp.572 0 -motor.cogging_dq_comp.573 0 -motor.cogging_dq_comp.574 0 -motor.cogging_dq_comp.575 0 -motor.cogging_dq_comp.576 0 -motor.cogging_dq_comp.577 0 -motor.cogging_dq_comp.578 0 -motor.cogging_dq_comp.579 0 -motor.cogging_dq_comp.580 0 -motor.cogging_dq_comp.581 0 -motor.cogging_dq_comp.582 0 -motor.cogging_dq_comp.583 0 -motor.cogging_dq_comp.584 0 -motor.cogging_dq_comp.585 0 -motor.cogging_dq_comp.586 0 -motor.cogging_dq_comp.587 0 -motor.cogging_dq_comp.588 0 -motor.cogging_dq_comp.589 0 -motor.cogging_dq_comp.590 0 -motor.cogging_dq_comp.591 0 -motor.cogging_dq_comp.592 0 -motor.cogging_dq_comp.593 0 -motor.cogging_dq_comp.594 0 -motor.cogging_dq_comp.595 0 -motor.cogging_dq_comp.596 0 -motor.cogging_dq_comp.597 0 -motor.cogging_dq_comp.598 0 -motor.cogging_dq_comp.599 0 -motor.cogging_dq_comp.600 0 -motor.cogging_dq_comp.601 0 -motor.cogging_dq_comp.602 0 -motor.cogging_dq_comp.603 0 -motor.cogging_dq_comp.604 0 -motor.cogging_dq_comp.605 0 -motor.cogging_dq_comp.606 0 -motor.cogging_dq_comp.607 0 -motor.cogging_dq_comp.608 0 -motor.cogging_dq_comp.609 0 -motor.cogging_dq_comp.610 0 -motor.cogging_dq_comp.611 0 -motor.cogging_dq_comp.612 0 -motor.cogging_dq_comp.613 0 -motor.cogging_dq_comp.614 0 -motor.cogging_dq_comp.615 0 -motor.cogging_dq_comp.616 0 -motor.cogging_dq_comp.617 0 -motor.cogging_dq_comp.618 0 -motor.cogging_dq_comp.619 0 -motor.cogging_dq_comp.620 0 -motor.cogging_dq_comp.621 0 -motor.cogging_dq_comp.622 0 -motor.cogging_dq_comp.623 0 -motor.cogging_dq_comp.624 0 -motor.cogging_dq_comp.625 0 -motor.cogging_dq_comp.626 0 -motor.cogging_dq_comp.627 0 -motor.cogging_dq_comp.628 0 -motor.cogging_dq_comp.629 0 -motor.cogging_dq_comp.630 0 -motor.cogging_dq_comp.631 0 -motor.cogging_dq_comp.632 0 -motor.cogging_dq_comp.633 0 -motor.cogging_dq_comp.634 0 -motor.cogging_dq_comp.635 0 -motor.cogging_dq_comp.636 0 -motor.cogging_dq_comp.637 0 -motor.cogging_dq_comp.638 0 -motor.cogging_dq_comp.639 0 -motor.cogging_dq_comp.640 0 -motor.cogging_dq_comp.641 0 -motor.cogging_dq_comp.642 0 -motor.cogging_dq_comp.643 0 -motor.cogging_dq_comp.644 0 -motor.cogging_dq_comp.645 0 -motor.cogging_dq_comp.646 0 -motor.cogging_dq_comp.647 0 -motor.cogging_dq_comp.648 0 -motor.cogging_dq_comp.649 0 -motor.cogging_dq_comp.650 0 -motor.cogging_dq_comp.651 0 -motor.cogging_dq_comp.652 0 -motor.cogging_dq_comp.653 0 -motor.cogging_dq_comp.654 0 -motor.cogging_dq_comp.655 0 -motor.cogging_dq_comp.656 0 -motor.cogging_dq_comp.657 0 -motor.cogging_dq_comp.658 0 -motor.cogging_dq_comp.659 0 -motor.cogging_dq_comp.660 0 -motor.cogging_dq_comp.661 0 -motor.cogging_dq_comp.662 0 -motor.cogging_dq_comp.663 0 -motor.cogging_dq_comp.664 0 -motor.cogging_dq_comp.665 0 -motor.cogging_dq_comp.666 0 -motor.cogging_dq_comp.667 0 -motor.cogging_dq_comp.668 0 -motor.cogging_dq_comp.669 0 -motor.cogging_dq_comp.670 0 -motor.cogging_dq_comp.671 0 -motor.cogging_dq_comp.672 0 -motor.cogging_dq_comp.673 0 -motor.cogging_dq_comp.674 0 -motor.cogging_dq_comp.675 0 -motor.cogging_dq_comp.676 0 -motor.cogging_dq_comp.677 0 -motor.cogging_dq_comp.678 0 -motor.cogging_dq_comp.679 0 -motor.cogging_dq_comp.680 0 -motor.cogging_dq_comp.681 0 -motor.cogging_dq_comp.682 0 -motor.cogging_dq_comp.683 0 -motor.cogging_dq_comp.684 0 -motor.cogging_dq_comp.685 0 -motor.cogging_dq_comp.686 0 -motor.cogging_dq_comp.687 0 -motor.cogging_dq_comp.688 0 -motor.cogging_dq_comp.689 0 -motor.cogging_dq_comp.690 0 -motor.cogging_dq_comp.691 0 -motor.cogging_dq_comp.692 0 -motor.cogging_dq_comp.693 0 -motor.cogging_dq_comp.694 0 -motor.cogging_dq_comp.695 0 -motor.cogging_dq_comp.696 0 -motor.cogging_dq_comp.697 0 -motor.cogging_dq_comp.698 0 -motor.cogging_dq_comp.699 0 -motor.cogging_dq_comp.700 0 -motor.cogging_dq_comp.701 0 -motor.cogging_dq_comp.702 0 -motor.cogging_dq_comp.703 0 -motor.cogging_dq_comp.704 0 -motor.cogging_dq_comp.705 0 -motor.cogging_dq_comp.706 0 -motor.cogging_dq_comp.707 0 -motor.cogging_dq_comp.708 0 -motor.cogging_dq_comp.709 0 -motor.cogging_dq_comp.710 0 -motor.cogging_dq_comp.711 0 -motor.cogging_dq_comp.712 0 -motor.cogging_dq_comp.713 0 -motor.cogging_dq_comp.714 0 -motor.cogging_dq_comp.715 0 -motor.cogging_dq_comp.716 0 -motor.cogging_dq_comp.717 0 -motor.cogging_dq_comp.718 0 -motor.cogging_dq_comp.719 0 -motor.cogging_dq_comp.720 0 -motor.cogging_dq_comp.721 0 -motor.cogging_dq_comp.722 0 -motor.cogging_dq_comp.723 0 -motor.cogging_dq_comp.724 0 -motor.cogging_dq_comp.725 0 -motor.cogging_dq_comp.726 0 -motor.cogging_dq_comp.727 0 -motor.cogging_dq_comp.728 0 -motor.cogging_dq_comp.729 0 -motor.cogging_dq_comp.730 0 -motor.cogging_dq_comp.731 0 -motor.cogging_dq_comp.732 0 -motor.cogging_dq_comp.733 0 -motor.cogging_dq_comp.734 0 -motor.cogging_dq_comp.735 0 -motor.cogging_dq_comp.736 0 -motor.cogging_dq_comp.737 0 -motor.cogging_dq_comp.738 0 -motor.cogging_dq_comp.739 0 -motor.cogging_dq_comp.740 0 -motor.cogging_dq_comp.741 0 -motor.cogging_dq_comp.742 0 -motor.cogging_dq_comp.743 0 -motor.cogging_dq_comp.744 0 -motor.cogging_dq_comp.745 0 -motor.cogging_dq_comp.746 0 -motor.cogging_dq_comp.747 0 -motor.cogging_dq_comp.748 0 -motor.cogging_dq_comp.749 0 -motor.cogging_dq_comp.750 0 -motor.cogging_dq_comp.751 0 -motor.cogging_dq_comp.752 0 -motor.cogging_dq_comp.753 0 -motor.cogging_dq_comp.754 0 -motor.cogging_dq_comp.755 0 -motor.cogging_dq_comp.756 0 -motor.cogging_dq_comp.757 0 -motor.cogging_dq_comp.758 0 -motor.cogging_dq_comp.759 0 -motor.cogging_dq_comp.760 0 -motor.cogging_dq_comp.761 0 -motor.cogging_dq_comp.762 0 -motor.cogging_dq_comp.763 0 -motor.cogging_dq_comp.764 0 -motor.cogging_dq_comp.765 0 -motor.cogging_dq_comp.766 0 -motor.cogging_dq_comp.767 0 -motor.cogging_dq_comp.768 0 -motor.cogging_dq_comp.769 0 -motor.cogging_dq_comp.770 0 -motor.cogging_dq_comp.771 0 -motor.cogging_dq_comp.772 0 -motor.cogging_dq_comp.773 0 -motor.cogging_dq_comp.774 0 -motor.cogging_dq_comp.775 0 -motor.cogging_dq_comp.776 0 -motor.cogging_dq_comp.777 0 -motor.cogging_dq_comp.778 0 -motor.cogging_dq_comp.779 0 -motor.cogging_dq_comp.780 0 -motor.cogging_dq_comp.781 0 -motor.cogging_dq_comp.782 0 -motor.cogging_dq_comp.783 0 -motor.cogging_dq_comp.784 0 -motor.cogging_dq_comp.785 0 -motor.cogging_dq_comp.786 0 -motor.cogging_dq_comp.787 0 -motor.cogging_dq_comp.788 0 -motor.cogging_dq_comp.789 0 -motor.cogging_dq_comp.790 0 -motor.cogging_dq_comp.791 0 -motor.cogging_dq_comp.792 0 -motor.cogging_dq_comp.793 0 -motor.cogging_dq_comp.794 0 -motor.cogging_dq_comp.795 0 -motor.cogging_dq_comp.796 0 -motor.cogging_dq_comp.797 0 -motor.cogging_dq_comp.798 0 -motor.cogging_dq_comp.799 0 -motor.cogging_dq_comp.800 0 -motor.cogging_dq_comp.801 0 -motor.cogging_dq_comp.802 0 -motor.cogging_dq_comp.803 0 -motor.cogging_dq_comp.804 0 -motor.cogging_dq_comp.805 0 -motor.cogging_dq_comp.806 0 -motor.cogging_dq_comp.807 0 -motor.cogging_dq_comp.808 0 -motor.cogging_dq_comp.809 0 -motor.cogging_dq_comp.810 0 -motor.cogging_dq_comp.811 0 -motor.cogging_dq_comp.812 0 -motor.cogging_dq_comp.813 0 -motor.cogging_dq_comp.814 0 -motor.cogging_dq_comp.815 0 -motor.cogging_dq_comp.816 0 -motor.cogging_dq_comp.817 0 -motor.cogging_dq_comp.818 0 -motor.cogging_dq_comp.819 0 -motor.cogging_dq_comp.820 0 -motor.cogging_dq_comp.821 0 -motor.cogging_dq_comp.822 0 -motor.cogging_dq_comp.823 0 -motor.cogging_dq_comp.824 0 -motor.cogging_dq_comp.825 0 -motor.cogging_dq_comp.826 0 -motor.cogging_dq_comp.827 0 -motor.cogging_dq_comp.828 0 -motor.cogging_dq_comp.829 0 -motor.cogging_dq_comp.830 0 -motor.cogging_dq_comp.831 0 -motor.cogging_dq_comp.832 0 -motor.cogging_dq_comp.833 0 -motor.cogging_dq_comp.834 0 -motor.cogging_dq_comp.835 0 -motor.cogging_dq_comp.836 0 -motor.cogging_dq_comp.837 0 -motor.cogging_dq_comp.838 0 -motor.cogging_dq_comp.839 0 -motor.cogging_dq_comp.840 0 -motor.cogging_dq_comp.841 0 -motor.cogging_dq_comp.842 0 -motor.cogging_dq_comp.843 0 -motor.cogging_dq_comp.844 0 -motor.cogging_dq_comp.845 0 -motor.cogging_dq_comp.846 0 -motor.cogging_dq_comp.847 0 -motor.cogging_dq_comp.848 0 -motor.cogging_dq_comp.849 0 -motor.cogging_dq_comp.850 0 -motor.cogging_dq_comp.851 0 -motor.cogging_dq_comp.852 0 -motor.cogging_dq_comp.853 0 -motor.cogging_dq_comp.854 0 -motor.cogging_dq_comp.855 0 -motor.cogging_dq_comp.856 0 -motor.cogging_dq_comp.857 0 -motor.cogging_dq_comp.858 0 -motor.cogging_dq_comp.859 0 -motor.cogging_dq_comp.860 0 -motor.cogging_dq_comp.861 0 -motor.cogging_dq_comp.862 0 -motor.cogging_dq_comp.863 0 -motor.cogging_dq_comp.864 0 -motor.cogging_dq_comp.865 0 -motor.cogging_dq_comp.866 0 -motor.cogging_dq_comp.867 0 -motor.cogging_dq_comp.868 0 -motor.cogging_dq_comp.869 0 -motor.cogging_dq_comp.870 0 -motor.cogging_dq_comp.871 0 -motor.cogging_dq_comp.872 0 -motor.cogging_dq_comp.873 0 -motor.cogging_dq_comp.874 0 -motor.cogging_dq_comp.875 0 -motor.cogging_dq_comp.876 0 -motor.cogging_dq_comp.877 0 -motor.cogging_dq_comp.878 0 -motor.cogging_dq_comp.879 0 -motor.cogging_dq_comp.880 0 -motor.cogging_dq_comp.881 0 -motor.cogging_dq_comp.882 0 -motor.cogging_dq_comp.883 0 -motor.cogging_dq_comp.884 0 -motor.cogging_dq_comp.885 0 -motor.cogging_dq_comp.886 0 -motor.cogging_dq_comp.887 0 -motor.cogging_dq_comp.888 0 -motor.cogging_dq_comp.889 0 -motor.cogging_dq_comp.890 0 -motor.cogging_dq_comp.891 0 -motor.cogging_dq_comp.892 0 -motor.cogging_dq_comp.893 0 -motor.cogging_dq_comp.894 0 -motor.cogging_dq_comp.895 0 -motor.cogging_dq_comp.896 0 -motor.cogging_dq_comp.897 0 -motor.cogging_dq_comp.898 0 -motor.cogging_dq_comp.899 0 -motor.cogging_dq_comp.900 0 -motor.cogging_dq_comp.901 0 -motor.cogging_dq_comp.902 0 -motor.cogging_dq_comp.903 0 -motor.cogging_dq_comp.904 0 -motor.cogging_dq_comp.905 0 -motor.cogging_dq_comp.906 0 -motor.cogging_dq_comp.907 0 -motor.cogging_dq_comp.908 0 -motor.cogging_dq_comp.909 0 -motor.cogging_dq_comp.910 0 -motor.cogging_dq_comp.911 0 -motor.cogging_dq_comp.912 0 -motor.cogging_dq_comp.913 0 -motor.cogging_dq_comp.914 0 -motor.cogging_dq_comp.915 0 -motor.cogging_dq_comp.916 0 -motor.cogging_dq_comp.917 0 -motor.cogging_dq_comp.918 0 -motor.cogging_dq_comp.919 0 -motor.cogging_dq_comp.920 0 -motor.cogging_dq_comp.921 0 -motor.cogging_dq_comp.922 0 -motor.cogging_dq_comp.923 0 -motor.cogging_dq_comp.924 0 -motor.cogging_dq_comp.925 0 -motor.cogging_dq_comp.926 0 -motor.cogging_dq_comp.927 0 -motor.cogging_dq_comp.928 0 -motor.cogging_dq_comp.929 0 -motor.cogging_dq_comp.930 0 -motor.cogging_dq_comp.931 0 -motor.cogging_dq_comp.932 0 -motor.cogging_dq_comp.933 0 -motor.cogging_dq_comp.934 0 -motor.cogging_dq_comp.935 0 -motor.cogging_dq_comp.936 0 -motor.cogging_dq_comp.937 0 -motor.cogging_dq_comp.938 0 -motor.cogging_dq_comp.939 0 -motor.cogging_dq_comp.940 0 -motor.cogging_dq_comp.941 0 -motor.cogging_dq_comp.942 0 -motor.cogging_dq_comp.943 0 -motor.cogging_dq_comp.944 0 -motor.cogging_dq_comp.945 0 -motor.cogging_dq_comp.946 0 -motor.cogging_dq_comp.947 0 -motor.cogging_dq_comp.948 0 -motor.cogging_dq_comp.949 0 -motor.cogging_dq_comp.950 0 -motor.cogging_dq_comp.951 0 -motor.cogging_dq_comp.952 0 -motor.cogging_dq_comp.953 0 -motor.cogging_dq_comp.954 0 -motor.cogging_dq_comp.955 0 -motor.cogging_dq_comp.956 0 -motor.cogging_dq_comp.957 0 -motor.cogging_dq_comp.958 0 -motor.cogging_dq_comp.959 0 -motor.cogging_dq_comp.960 0 -motor.cogging_dq_comp.961 0 -motor.cogging_dq_comp.962 0 -motor.cogging_dq_comp.963 0 -motor.cogging_dq_comp.964 0 -motor.cogging_dq_comp.965 0 -motor.cogging_dq_comp.966 0 -motor.cogging_dq_comp.967 0 -motor.cogging_dq_comp.968 0 -motor.cogging_dq_comp.969 0 -motor.cogging_dq_comp.970 0 -motor.cogging_dq_comp.971 0 -motor.cogging_dq_comp.972 0 -motor.cogging_dq_comp.973 0 -motor.cogging_dq_comp.974 0 -motor.cogging_dq_comp.975 0 -motor.cogging_dq_comp.976 0 -motor.cogging_dq_comp.977 0 -motor.cogging_dq_comp.978 0 -motor.cogging_dq_comp.979 0 -motor.cogging_dq_comp.980 0 -motor.cogging_dq_comp.981 0 -motor.cogging_dq_comp.982 0 -motor.cogging_dq_comp.983 0 -motor.cogging_dq_comp.984 0 -motor.cogging_dq_comp.985 0 -motor.cogging_dq_comp.986 0 -motor.cogging_dq_comp.987 0 -motor.cogging_dq_comp.988 0 -motor.cogging_dq_comp.989 0 -motor.cogging_dq_comp.990 0 -motor.cogging_dq_comp.991 0 -motor.cogging_dq_comp.992 0 -motor.cogging_dq_comp.993 0 -motor.cogging_dq_comp.994 0 -motor.cogging_dq_comp.995 0 -motor.cogging_dq_comp.996 0 -motor.cogging_dq_comp.997 0 -motor.cogging_dq_comp.998 0 -motor.cogging_dq_comp.999 0 -motor.cogging_dq_comp.1000 0 -motor.cogging_dq_comp.1001 0 -motor.cogging_dq_comp.1002 0 -motor.cogging_dq_comp.1003 0 -motor.cogging_dq_comp.1004 0 -motor.cogging_dq_comp.1005 0 -motor.cogging_dq_comp.1006 0 -motor.cogging_dq_comp.1007 0 -motor.cogging_dq_comp.1008 0 -motor.cogging_dq_comp.1009 0 -motor.cogging_dq_comp.1010 0 -motor.cogging_dq_comp.1011 0 -motor.cogging_dq_comp.1012 0 -motor.cogging_dq_comp.1013 0 -motor.cogging_dq_comp.1014 0 -motor.cogging_dq_comp.1015 0 -motor.cogging_dq_comp.1016 0 -motor.cogging_dq_comp.1017 0 -motor.cogging_dq_comp.1018 0 -motor.cogging_dq_comp.1019 0 -motor.cogging_dq_comp.1020 0 -motor.cogging_dq_comp.1021 0 -motor.cogging_dq_comp.1022 0 -motor.cogging_dq_comp.1023 0 -drv8323_conf.dis_cpuv 0 -drv8323_conf.dis_gdf 0 -drv8323_conf.otw_rep 0 -drv8323_conf.pwm_mode 1 -drv8323_conf.pwm_1x_asynchronous 0 -drv8323_conf.pwm_1x_dir 0 -drv8323_conf.idrivep_hs_ma 150 -drv8323_conf.idriven_hs_ma 300 -drv8323_conf.cbc 1 -drv8323_conf.tdrive_ns 1000 -drv8323_conf.idrivep_ls_ma 150 -drv8323_conf.idriven_ls_ma 300 -drv8323_conf.tretry 0 -drv8323_conf.dead_time_ns 50 -drv8323_conf.ocp_mode 0 -drv8323_conf.ocp_deg_us 4 -drv8323_conf.vds_lvl_mv 700 -drv8323_conf.csa_fet 0 -drv8323_conf.vref_div 1 -drv8323_conf.ls_ref 0 -drv8323_conf.csa_gain 20 -drv8323_conf.dis_sen 0 -drv8323_conf.sen_lvl_mv 500 -servo.pwm_rate_hz 30000 -servo.i_gain 20.000000 -servo.current_sense_ohm 0.000500 -servo.pwm_comp_off 0.027000 -servo.pwm_comp_mag 0.005000 -servo.pwm_scale 1.000000 -servo.max_voltage 56.000000 -servo.max_power_W 450.000000 -servo.derate_temperature 50.000000 -servo.fault_temperature 75.000000 -servo.enable_motor_temperature 0 -servo.motor_derate_temperature 50.000000 -servo.motor_fault_temperature nan -servo.velocity_threshold 0.000000 -servo.position_derate 0.020000 -servo.adc_cur_cycles 2 -servo.adc_aux_cycles 47 -servo.pid_dq.kp 1.392894 -servo.pid_dq.ki 2666.149170 -servo.pid_position.kp 0.000000 -servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.000000 -servo.pid_position.iratelimit -1.000000 -servo.pid_position.ilimit 0.000000 -servo.pid_position.max_desired_rate 0.000000 -servo.pid_position.sign -1 -servo.current_feedforward 1.000000 -servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit nan -servo.voltage_mode_control 0 -servo.fixed_voltage_mode 0 -servo.fixed_voltage_control_V 0.000000 -servo.max_position_slip nan -servo.max_velocity_slip nan -servo.default_timeout_s 0.100000 -servo.timeout_max_torque_Nm 5.000000 -servo.timeout_mode 12 -servo.flux_brake_min_voltage 53.000000 -servo.flux_brake_resistance_ohm 0.025000 -servo.max_current_A 2.000000 -servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 -servo.max_velocity_derate 2.000000 -servo.cooldown_cycles 256 -servo.velocity_zero_capture_threshold 0.050000 -servo.timing_fault 0 -servo.emit_debug 0 -servopos.position_min nan -servopos.position_max nan -id.id 35 -can.prefix 0 - diff --git a/config/moteus/de1/old.config b/config/moteus/de1/old.config deleted file mode 100644 index f44764268..000000000 --- a/config/moteus/de1/old.config +++ /dev/null @@ -1,1399 +0,0 @@ -uuid.uuid.0 210 -uuid.uuid.1 42 -uuid.uuid.2 55 -uuid.uuid.3 197 -uuid.uuid.4 115 -uuid.uuid.5 183 -uuid.uuid.6 70 -uuid.uuid.7 194 -uuid.uuid.8 179 -uuid.uuid.9 54 -uuid.uuid.10 50 -uuid.uuid.11 137 -uuid.uuid.12 91 -uuid.uuid.13 149 -uuid.uuid.14 200 -uuid.uuid.15 194 -clock.hsitrim 64 -aux1.i2c.i2c_hz 400000 -aux1.i2c.i2c_mode 1 -aux1.i2c.pullup 1 -aux1.i2c.devices.0.type 1 -aux1.i2c.devices.0.address 64 -aux1.i2c.devices.0.poll_rate_us 1000 -aux1.i2c.devices.1.type 0 -aux1.i2c.devices.1.address 64 -aux1.i2c.devices.1.poll_rate_us 1000 -aux1.i2c.devices.2.type 0 -aux1.i2c.devices.2.address 64 -aux1.i2c.devices.2.poll_rate_us 1000 -aux1.spi.mode 1 -aux1.spi.rate_hz 12000000 -aux1.spi.filter_us 64 -aux1.spi.bct 0 -aux1.uart.mode 0 -aux1.uart.baud_rate 115200 -aux1.uart.poll_rate_us 100 -aux1.uart.rs422 0 -aux1.uart.cui_amt21_address 84 -aux1.quadrature.enabled 0 -aux1.quadrature.cpr 16384 -aux1.hall.enabled 0 -aux1.hall.polarity 0 -aux1.index.enabled 0 -aux1.sine_cosine.enabled 0 -aux1.sine_cosine.common 1700 -aux1.i2c_startup_delay_ms 30 -aux1.pins.0.mode 0 -aux1.pins.0.pull 0 -aux1.pins.1.mode 0 -aux1.pins.1.pull 0 -aux1.pins.2.mode 0 -aux1.pins.2.pull 0 -aux1.pins.3.mode 13 -aux1.pins.3.pull 1 -aux1.pins.4.mode 13 -aux1.pins.4.pull 1 -aux2.i2c.i2c_hz 400000 -aux2.i2c.i2c_mode 1 -aux2.i2c.pullup 0 -aux2.i2c.devices.0.type 0 -aux2.i2c.devices.0.address 64 -aux2.i2c.devices.0.poll_rate_us 1000 -aux2.i2c.devices.1.type 0 -aux2.i2c.devices.1.address 64 -aux2.i2c.devices.1.poll_rate_us 1000 -aux2.i2c.devices.2.type 0 -aux2.i2c.devices.2.address 64 -aux2.i2c.devices.2.poll_rate_us 1000 -aux2.spi.mode 1 -aux2.spi.rate_hz 12000000 -aux2.spi.filter_us 64 -aux2.spi.bct 0 -aux2.uart.mode 0 -aux2.uart.baud_rate 115200 -aux2.uart.poll_rate_us 100 -aux2.uart.rs422 0 -aux2.uart.cui_amt21_address 84 -aux2.quadrature.enabled 0 -aux2.quadrature.cpr 16384 -aux2.hall.enabled 1 -aux2.hall.polarity 0 -aux2.index.enabled 0 -aux2.sine_cosine.enabled 0 -aux2.sine_cosine.common 1700 -aux2.i2c_startup_delay_ms 30 -aux2.pins.0.mode 6 -aux2.pins.0.pull 1 -aux2.pins.1.mode 6 -aux2.pins.1.pull 1 -aux2.pins.2.mode 6 -aux2.pins.2.pull 1 -aux2.pins.3.mode 0 -aux2.pins.3.pull 0 -aux2.pins.4.mode 0 -aux2.pins.4.pull 0 -motor_position.sources.0.aux_number 2 -motor_position.sources.0.type 4 -motor_position.sources.0.i2c_device 0 -motor_position.sources.0.incremental_index -1 -motor_position.sources.0.cpr 42 -motor_position.sources.0.offset -1.000000 -motor_position.sources.0.sign 1 -motor_position.sources.0.debug_override -1 -motor_position.sources.0.reference 0 -motor_position.sources.0.pll_filter_hz 100.000000 -motor_position.sources.0.compensation_table.0 0.000000 -motor_position.sources.0.compensation_table.1 0.000000 -motor_position.sources.0.compensation_table.2 0.000000 -motor_position.sources.0.compensation_table.3 0.000000 -motor_position.sources.0.compensation_table.4 0.000000 -motor_position.sources.0.compensation_table.5 0.000000 -motor_position.sources.0.compensation_table.6 0.000000 -motor_position.sources.0.compensation_table.7 0.000000 -motor_position.sources.0.compensation_table.8 0.000000 -motor_position.sources.0.compensation_table.9 0.000000 -motor_position.sources.0.compensation_table.10 0.000000 -motor_position.sources.0.compensation_table.11 0.000000 -motor_position.sources.0.compensation_table.12 0.000000 -motor_position.sources.0.compensation_table.13 0.000000 -motor_position.sources.0.compensation_table.14 0.000000 -motor_position.sources.0.compensation_table.15 0.000000 -motor_position.sources.0.compensation_table.16 0.000000 -motor_position.sources.0.compensation_table.17 0.000000 -motor_position.sources.0.compensation_table.18 0.000000 -motor_position.sources.0.compensation_table.19 0.000000 -motor_position.sources.0.compensation_table.20 0.000000 -motor_position.sources.0.compensation_table.21 0.000000 -motor_position.sources.0.compensation_table.22 0.000000 -motor_position.sources.0.compensation_table.23 0.000000 -motor_position.sources.0.compensation_table.24 0.000000 -motor_position.sources.0.compensation_table.25 0.000000 -motor_position.sources.0.compensation_table.26 0.000000 -motor_position.sources.0.compensation_table.27 0.000000 -motor_position.sources.0.compensation_table.28 0.000000 -motor_position.sources.0.compensation_table.29 0.000000 -motor_position.sources.0.compensation_table.30 0.000000 -motor_position.sources.0.compensation_table.31 0.000000 -motor_position.sources.1.aux_number 1 -motor_position.sources.1.type 7 -motor_position.sources.1.i2c_device 0 -motor_position.sources.1.incremental_index -1 -motor_position.sources.1.cpr 16384 -motor_position.sources.1.offset 0.000000 -motor_position.sources.1.sign 1 -motor_position.sources.1.debug_override -1 -motor_position.sources.1.reference 1 -motor_position.sources.1.pll_filter_hz 100.000000 -motor_position.sources.1.compensation_table.0 0.000000 -motor_position.sources.1.compensation_table.1 0.000000 -motor_position.sources.1.compensation_table.2 0.000000 -motor_position.sources.1.compensation_table.3 0.000000 -motor_position.sources.1.compensation_table.4 0.000000 -motor_position.sources.1.compensation_table.5 0.000000 -motor_position.sources.1.compensation_table.6 0.000000 -motor_position.sources.1.compensation_table.7 0.000000 -motor_position.sources.1.compensation_table.8 0.000000 -motor_position.sources.1.compensation_table.9 0.000000 -motor_position.sources.1.compensation_table.10 0.000000 -motor_position.sources.1.compensation_table.11 0.000000 -motor_position.sources.1.compensation_table.12 0.000000 -motor_position.sources.1.compensation_table.13 0.000000 -motor_position.sources.1.compensation_table.14 0.000000 -motor_position.sources.1.compensation_table.15 0.000000 -motor_position.sources.1.compensation_table.16 0.000000 -motor_position.sources.1.compensation_table.17 0.000000 -motor_position.sources.1.compensation_table.18 0.000000 -motor_position.sources.1.compensation_table.19 0.000000 -motor_position.sources.1.compensation_table.20 0.000000 -motor_position.sources.1.compensation_table.21 0.000000 -motor_position.sources.1.compensation_table.22 0.000000 -motor_position.sources.1.compensation_table.23 0.000000 -motor_position.sources.1.compensation_table.24 0.000000 -motor_position.sources.1.compensation_table.25 0.000000 -motor_position.sources.1.compensation_table.26 0.000000 -motor_position.sources.1.compensation_table.27 0.000000 -motor_position.sources.1.compensation_table.28 0.000000 -motor_position.sources.1.compensation_table.29 0.000000 -motor_position.sources.1.compensation_table.30 0.000000 -motor_position.sources.1.compensation_table.31 0.000000 -motor_position.sources.2.aux_number 1 -motor_position.sources.2.type 0 -motor_position.sources.2.i2c_device 0 -motor_position.sources.2.incremental_index -1 -motor_position.sources.2.cpr 16384 -motor_position.sources.2.offset 0.000000 -motor_position.sources.2.sign 1 -motor_position.sources.2.debug_override -1 -motor_position.sources.2.reference 0 -motor_position.sources.2.pll_filter_hz 400.000000 -motor_position.sources.2.compensation_table.0 0.000000 -motor_position.sources.2.compensation_table.1 0.000000 -motor_position.sources.2.compensation_table.2 0.000000 -motor_position.sources.2.compensation_table.3 0.000000 -motor_position.sources.2.compensation_table.4 0.000000 -motor_position.sources.2.compensation_table.5 0.000000 -motor_position.sources.2.compensation_table.6 0.000000 -motor_position.sources.2.compensation_table.7 0.000000 -motor_position.sources.2.compensation_table.8 0.000000 -motor_position.sources.2.compensation_table.9 0.000000 -motor_position.sources.2.compensation_table.10 0.000000 -motor_position.sources.2.compensation_table.11 0.000000 -motor_position.sources.2.compensation_table.12 0.000000 -motor_position.sources.2.compensation_table.13 0.000000 -motor_position.sources.2.compensation_table.14 0.000000 -motor_position.sources.2.compensation_table.15 0.000000 -motor_position.sources.2.compensation_table.16 0.000000 -motor_position.sources.2.compensation_table.17 0.000000 -motor_position.sources.2.compensation_table.18 0.000000 -motor_position.sources.2.compensation_table.19 0.000000 -motor_position.sources.2.compensation_table.20 0.000000 -motor_position.sources.2.compensation_table.21 0.000000 -motor_position.sources.2.compensation_table.22 0.000000 -motor_position.sources.2.compensation_table.23 0.000000 -motor_position.sources.2.compensation_table.24 0.000000 -motor_position.sources.2.compensation_table.25 0.000000 -motor_position.sources.2.compensation_table.26 0.000000 -motor_position.sources.2.compensation_table.27 0.000000 -motor_position.sources.2.compensation_table.28 0.000000 -motor_position.sources.2.compensation_table.29 0.000000 -motor_position.sources.2.compensation_table.30 0.000000 -motor_position.sources.2.compensation_table.31 0.000000 -motor_position.commutation_source 0 -motor_position.output.source 0 -motor_position.output.offset 0.000000 -motor_position.output.sign 1 -motor_position.output.reference_source -1 -motor_position.rotor_to_output_ratio 1.000000 -motor.poles 14 -motor.phase_invert 0 -motor.resistance_ohm 2.629306 -motor.v_per_hz 0.504131 -motor.offset.0 0.000000 -motor.offset.1 0.000000 -motor.offset.2 0.000000 -motor.offset.3 0.000000 -motor.offset.4 0.000000 -motor.offset.5 0.000000 -motor.offset.6 0.000000 -motor.offset.7 0.000000 -motor.offset.8 0.000000 -motor.offset.9 0.000000 -motor.offset.10 0.000000 -motor.offset.11 0.000000 -motor.offset.12 0.000000 -motor.offset.13 0.000000 -motor.offset.14 0.000000 -motor.offset.15 0.000000 -motor.offset.16 0.000000 -motor.offset.17 0.000000 -motor.offset.18 0.000000 -motor.offset.19 0.000000 -motor.offset.20 0.000000 -motor.offset.21 0.000000 -motor.offset.22 0.000000 -motor.offset.23 0.000000 -motor.offset.24 0.000000 -motor.offset.25 0.000000 -motor.offset.26 0.000000 -motor.offset.27 0.000000 -motor.offset.28 0.000000 -motor.offset.29 0.000000 -motor.offset.30 0.000000 -motor.offset.31 0.000000 -motor.offset.32 0.000000 -motor.offset.33 0.000000 -motor.offset.34 0.000000 -motor.offset.35 0.000000 -motor.offset.36 0.000000 -motor.offset.37 0.000000 -motor.offset.38 0.000000 -motor.offset.39 0.000000 -motor.offset.40 0.000000 -motor.offset.41 0.000000 -motor.offset.42 0.000000 -motor.offset.43 0.000000 -motor.offset.44 0.000000 -motor.offset.45 0.000000 -motor.offset.46 0.000000 -motor.offset.47 0.000000 -motor.offset.48 0.000000 -motor.offset.49 0.000000 -motor.offset.50 0.000000 -motor.offset.51 0.000000 -motor.offset.52 0.000000 -motor.offset.53 0.000000 -motor.offset.54 0.000000 -motor.offset.55 0.000000 -motor.offset.56 0.000000 -motor.offset.57 0.000000 -motor.offset.58 0.000000 -motor.offset.59 0.000000 -motor.offset.60 0.000000 -motor.offset.61 0.000000 -motor.offset.62 0.000000 -motor.offset.63 0.000000 -motor.rotation_current_cutoff_A 10000.000000 -motor.rotation_current_scale 0.050000 -motor.rotation_torque_scale 14.700000 -motor.cogging_dq_scale 0.000000 -motor.cogging_dq_comp.0 0 -motor.cogging_dq_comp.1 0 -motor.cogging_dq_comp.2 0 -motor.cogging_dq_comp.3 0 -motor.cogging_dq_comp.4 0 -motor.cogging_dq_comp.5 0 -motor.cogging_dq_comp.6 0 -motor.cogging_dq_comp.7 0 -motor.cogging_dq_comp.8 0 -motor.cogging_dq_comp.9 0 -motor.cogging_dq_comp.10 0 -motor.cogging_dq_comp.11 0 -motor.cogging_dq_comp.12 0 -motor.cogging_dq_comp.13 0 -motor.cogging_dq_comp.14 0 -motor.cogging_dq_comp.15 0 -motor.cogging_dq_comp.16 0 -motor.cogging_dq_comp.17 0 -motor.cogging_dq_comp.18 0 -motor.cogging_dq_comp.19 0 -motor.cogging_dq_comp.20 0 -motor.cogging_dq_comp.21 0 -motor.cogging_dq_comp.22 0 -motor.cogging_dq_comp.23 0 -motor.cogging_dq_comp.24 0 -motor.cogging_dq_comp.25 0 -motor.cogging_dq_comp.26 0 -motor.cogging_dq_comp.27 0 -motor.cogging_dq_comp.28 0 -motor.cogging_dq_comp.29 0 -motor.cogging_dq_comp.30 0 -motor.cogging_dq_comp.31 0 -motor.cogging_dq_comp.32 0 -motor.cogging_dq_comp.33 0 -motor.cogging_dq_comp.34 0 -motor.cogging_dq_comp.35 0 -motor.cogging_dq_comp.36 0 -motor.cogging_dq_comp.37 0 -motor.cogging_dq_comp.38 0 -motor.cogging_dq_comp.39 0 -motor.cogging_dq_comp.40 0 -motor.cogging_dq_comp.41 0 -motor.cogging_dq_comp.42 0 -motor.cogging_dq_comp.43 0 -motor.cogging_dq_comp.44 0 -motor.cogging_dq_comp.45 0 -motor.cogging_dq_comp.46 0 -motor.cogging_dq_comp.47 0 -motor.cogging_dq_comp.48 0 -motor.cogging_dq_comp.49 0 -motor.cogging_dq_comp.50 0 -motor.cogging_dq_comp.51 0 -motor.cogging_dq_comp.52 0 -motor.cogging_dq_comp.53 0 -motor.cogging_dq_comp.54 0 -motor.cogging_dq_comp.55 0 -motor.cogging_dq_comp.56 0 -motor.cogging_dq_comp.57 0 -motor.cogging_dq_comp.58 0 -motor.cogging_dq_comp.59 0 -motor.cogging_dq_comp.60 0 -motor.cogging_dq_comp.61 0 -motor.cogging_dq_comp.62 0 -motor.cogging_dq_comp.63 0 -motor.cogging_dq_comp.64 0 -motor.cogging_dq_comp.65 0 -motor.cogging_dq_comp.66 0 -motor.cogging_dq_comp.67 0 -motor.cogging_dq_comp.68 0 -motor.cogging_dq_comp.69 0 -motor.cogging_dq_comp.70 0 -motor.cogging_dq_comp.71 0 -motor.cogging_dq_comp.72 0 -motor.cogging_dq_comp.73 0 -motor.cogging_dq_comp.74 0 -motor.cogging_dq_comp.75 0 -motor.cogging_dq_comp.76 0 -motor.cogging_dq_comp.77 0 -motor.cogging_dq_comp.78 0 -motor.cogging_dq_comp.79 0 -motor.cogging_dq_comp.80 0 -motor.cogging_dq_comp.81 0 -motor.cogging_dq_comp.82 0 -motor.cogging_dq_comp.83 0 -motor.cogging_dq_comp.84 0 -motor.cogging_dq_comp.85 0 -motor.cogging_dq_comp.86 0 -motor.cogging_dq_comp.87 0 -motor.cogging_dq_comp.88 0 -motor.cogging_dq_comp.89 0 -motor.cogging_dq_comp.90 0 -motor.cogging_dq_comp.91 0 -motor.cogging_dq_comp.92 0 -motor.cogging_dq_comp.93 0 -motor.cogging_dq_comp.94 0 -motor.cogging_dq_comp.95 0 -motor.cogging_dq_comp.96 0 -motor.cogging_dq_comp.97 0 -motor.cogging_dq_comp.98 0 -motor.cogging_dq_comp.99 0 -motor.cogging_dq_comp.100 0 -motor.cogging_dq_comp.101 0 -motor.cogging_dq_comp.102 0 -motor.cogging_dq_comp.103 0 -motor.cogging_dq_comp.104 0 -motor.cogging_dq_comp.105 0 -motor.cogging_dq_comp.106 0 -motor.cogging_dq_comp.107 0 -motor.cogging_dq_comp.108 0 -motor.cogging_dq_comp.109 0 -motor.cogging_dq_comp.110 0 -motor.cogging_dq_comp.111 0 -motor.cogging_dq_comp.112 0 -motor.cogging_dq_comp.113 0 -motor.cogging_dq_comp.114 0 -motor.cogging_dq_comp.115 0 -motor.cogging_dq_comp.116 0 -motor.cogging_dq_comp.117 0 -motor.cogging_dq_comp.118 0 -motor.cogging_dq_comp.119 0 -motor.cogging_dq_comp.120 0 -motor.cogging_dq_comp.121 0 -motor.cogging_dq_comp.122 0 -motor.cogging_dq_comp.123 0 -motor.cogging_dq_comp.124 0 -motor.cogging_dq_comp.125 0 -motor.cogging_dq_comp.126 0 -motor.cogging_dq_comp.127 0 -motor.cogging_dq_comp.128 0 -motor.cogging_dq_comp.129 0 -motor.cogging_dq_comp.130 0 -motor.cogging_dq_comp.131 0 -motor.cogging_dq_comp.132 0 -motor.cogging_dq_comp.133 0 -motor.cogging_dq_comp.134 0 -motor.cogging_dq_comp.135 0 -motor.cogging_dq_comp.136 0 -motor.cogging_dq_comp.137 0 -motor.cogging_dq_comp.138 0 -motor.cogging_dq_comp.139 0 -motor.cogging_dq_comp.140 0 -motor.cogging_dq_comp.141 0 -motor.cogging_dq_comp.142 0 -motor.cogging_dq_comp.143 0 -motor.cogging_dq_comp.144 0 -motor.cogging_dq_comp.145 0 -motor.cogging_dq_comp.146 0 -motor.cogging_dq_comp.147 0 -motor.cogging_dq_comp.148 0 -motor.cogging_dq_comp.149 0 -motor.cogging_dq_comp.150 0 -motor.cogging_dq_comp.151 0 -motor.cogging_dq_comp.152 0 -motor.cogging_dq_comp.153 0 -motor.cogging_dq_comp.154 0 -motor.cogging_dq_comp.155 0 -motor.cogging_dq_comp.156 0 -motor.cogging_dq_comp.157 0 -motor.cogging_dq_comp.158 0 -motor.cogging_dq_comp.159 0 -motor.cogging_dq_comp.160 0 -motor.cogging_dq_comp.161 0 -motor.cogging_dq_comp.162 0 -motor.cogging_dq_comp.163 0 -motor.cogging_dq_comp.164 0 -motor.cogging_dq_comp.165 0 -motor.cogging_dq_comp.166 0 -motor.cogging_dq_comp.167 0 -motor.cogging_dq_comp.168 0 -motor.cogging_dq_comp.169 0 -motor.cogging_dq_comp.170 0 -motor.cogging_dq_comp.171 0 -motor.cogging_dq_comp.172 0 -motor.cogging_dq_comp.173 0 -motor.cogging_dq_comp.174 0 -motor.cogging_dq_comp.175 0 -motor.cogging_dq_comp.176 0 -motor.cogging_dq_comp.177 0 -motor.cogging_dq_comp.178 0 -motor.cogging_dq_comp.179 0 -motor.cogging_dq_comp.180 0 -motor.cogging_dq_comp.181 0 -motor.cogging_dq_comp.182 0 -motor.cogging_dq_comp.183 0 -motor.cogging_dq_comp.184 0 -motor.cogging_dq_comp.185 0 -motor.cogging_dq_comp.186 0 -motor.cogging_dq_comp.187 0 -motor.cogging_dq_comp.188 0 -motor.cogging_dq_comp.189 0 -motor.cogging_dq_comp.190 0 -motor.cogging_dq_comp.191 0 -motor.cogging_dq_comp.192 0 -motor.cogging_dq_comp.193 0 -motor.cogging_dq_comp.194 0 -motor.cogging_dq_comp.195 0 -motor.cogging_dq_comp.196 0 -motor.cogging_dq_comp.197 0 -motor.cogging_dq_comp.198 0 -motor.cogging_dq_comp.199 0 -motor.cogging_dq_comp.200 0 -motor.cogging_dq_comp.201 0 -motor.cogging_dq_comp.202 0 -motor.cogging_dq_comp.203 0 -motor.cogging_dq_comp.204 0 -motor.cogging_dq_comp.205 0 -motor.cogging_dq_comp.206 0 -motor.cogging_dq_comp.207 0 -motor.cogging_dq_comp.208 0 -motor.cogging_dq_comp.209 0 -motor.cogging_dq_comp.210 0 -motor.cogging_dq_comp.211 0 -motor.cogging_dq_comp.212 0 -motor.cogging_dq_comp.213 0 -motor.cogging_dq_comp.214 0 -motor.cogging_dq_comp.215 0 -motor.cogging_dq_comp.216 0 -motor.cogging_dq_comp.217 0 -motor.cogging_dq_comp.218 0 -motor.cogging_dq_comp.219 0 -motor.cogging_dq_comp.220 0 -motor.cogging_dq_comp.221 0 -motor.cogging_dq_comp.222 0 -motor.cogging_dq_comp.223 0 -motor.cogging_dq_comp.224 0 -motor.cogging_dq_comp.225 0 -motor.cogging_dq_comp.226 0 -motor.cogging_dq_comp.227 0 -motor.cogging_dq_comp.228 0 -motor.cogging_dq_comp.229 0 -motor.cogging_dq_comp.230 0 -motor.cogging_dq_comp.231 0 -motor.cogging_dq_comp.232 0 -motor.cogging_dq_comp.233 0 -motor.cogging_dq_comp.234 0 -motor.cogging_dq_comp.235 0 -motor.cogging_dq_comp.236 0 -motor.cogging_dq_comp.237 0 -motor.cogging_dq_comp.238 0 -motor.cogging_dq_comp.239 0 -motor.cogging_dq_comp.240 0 -motor.cogging_dq_comp.241 0 -motor.cogging_dq_comp.242 0 -motor.cogging_dq_comp.243 0 -motor.cogging_dq_comp.244 0 -motor.cogging_dq_comp.245 0 -motor.cogging_dq_comp.246 0 -motor.cogging_dq_comp.247 0 -motor.cogging_dq_comp.248 0 -motor.cogging_dq_comp.249 0 -motor.cogging_dq_comp.250 0 -motor.cogging_dq_comp.251 0 -motor.cogging_dq_comp.252 0 -motor.cogging_dq_comp.253 0 -motor.cogging_dq_comp.254 0 -motor.cogging_dq_comp.255 0 -motor.cogging_dq_comp.256 0 -motor.cogging_dq_comp.257 0 -motor.cogging_dq_comp.258 0 -motor.cogging_dq_comp.259 0 -motor.cogging_dq_comp.260 0 -motor.cogging_dq_comp.261 0 -motor.cogging_dq_comp.262 0 -motor.cogging_dq_comp.263 0 -motor.cogging_dq_comp.264 0 -motor.cogging_dq_comp.265 0 -motor.cogging_dq_comp.266 0 -motor.cogging_dq_comp.267 0 -motor.cogging_dq_comp.268 0 -motor.cogging_dq_comp.269 0 -motor.cogging_dq_comp.270 0 -motor.cogging_dq_comp.271 0 -motor.cogging_dq_comp.272 0 -motor.cogging_dq_comp.273 0 -motor.cogging_dq_comp.274 0 -motor.cogging_dq_comp.275 0 -motor.cogging_dq_comp.276 0 -motor.cogging_dq_comp.277 0 -motor.cogging_dq_comp.278 0 -motor.cogging_dq_comp.279 0 -motor.cogging_dq_comp.280 0 -motor.cogging_dq_comp.281 0 -motor.cogging_dq_comp.282 0 -motor.cogging_dq_comp.283 0 -motor.cogging_dq_comp.284 0 -motor.cogging_dq_comp.285 0 -motor.cogging_dq_comp.286 0 -motor.cogging_dq_comp.287 0 -motor.cogging_dq_comp.288 0 -motor.cogging_dq_comp.289 0 -motor.cogging_dq_comp.290 0 -motor.cogging_dq_comp.291 0 -motor.cogging_dq_comp.292 0 -motor.cogging_dq_comp.293 0 -motor.cogging_dq_comp.294 0 -motor.cogging_dq_comp.295 0 -motor.cogging_dq_comp.296 0 -motor.cogging_dq_comp.297 0 -motor.cogging_dq_comp.298 0 -motor.cogging_dq_comp.299 0 -motor.cogging_dq_comp.300 0 -motor.cogging_dq_comp.301 0 -motor.cogging_dq_comp.302 0 -motor.cogging_dq_comp.303 0 -motor.cogging_dq_comp.304 0 -motor.cogging_dq_comp.305 0 -motor.cogging_dq_comp.306 0 -motor.cogging_dq_comp.307 0 -motor.cogging_dq_comp.308 0 -motor.cogging_dq_comp.309 0 -motor.cogging_dq_comp.310 0 -motor.cogging_dq_comp.311 0 -motor.cogging_dq_comp.312 0 -motor.cogging_dq_comp.313 0 -motor.cogging_dq_comp.314 0 -motor.cogging_dq_comp.315 0 -motor.cogging_dq_comp.316 0 -motor.cogging_dq_comp.317 0 -motor.cogging_dq_comp.318 0 -motor.cogging_dq_comp.319 0 -motor.cogging_dq_comp.320 0 -motor.cogging_dq_comp.321 0 -motor.cogging_dq_comp.322 0 -motor.cogging_dq_comp.323 0 -motor.cogging_dq_comp.324 0 -motor.cogging_dq_comp.325 0 -motor.cogging_dq_comp.326 0 -motor.cogging_dq_comp.327 0 -motor.cogging_dq_comp.328 0 -motor.cogging_dq_comp.329 0 -motor.cogging_dq_comp.330 0 -motor.cogging_dq_comp.331 0 -motor.cogging_dq_comp.332 0 -motor.cogging_dq_comp.333 0 -motor.cogging_dq_comp.334 0 -motor.cogging_dq_comp.335 0 -motor.cogging_dq_comp.336 0 -motor.cogging_dq_comp.337 0 -motor.cogging_dq_comp.338 0 -motor.cogging_dq_comp.339 0 -motor.cogging_dq_comp.340 0 -motor.cogging_dq_comp.341 0 -motor.cogging_dq_comp.342 0 -motor.cogging_dq_comp.343 0 -motor.cogging_dq_comp.344 0 -motor.cogging_dq_comp.345 0 -motor.cogging_dq_comp.346 0 -motor.cogging_dq_comp.347 0 -motor.cogging_dq_comp.348 0 -motor.cogging_dq_comp.349 0 -motor.cogging_dq_comp.350 0 -motor.cogging_dq_comp.351 0 -motor.cogging_dq_comp.352 0 -motor.cogging_dq_comp.353 0 -motor.cogging_dq_comp.354 0 -motor.cogging_dq_comp.355 0 -motor.cogging_dq_comp.356 0 -motor.cogging_dq_comp.357 0 -motor.cogging_dq_comp.358 0 -motor.cogging_dq_comp.359 0 -motor.cogging_dq_comp.360 0 -motor.cogging_dq_comp.361 0 -motor.cogging_dq_comp.362 0 -motor.cogging_dq_comp.363 0 -motor.cogging_dq_comp.364 0 -motor.cogging_dq_comp.365 0 -motor.cogging_dq_comp.366 0 -motor.cogging_dq_comp.367 0 -motor.cogging_dq_comp.368 0 -motor.cogging_dq_comp.369 0 -motor.cogging_dq_comp.370 0 -motor.cogging_dq_comp.371 0 -motor.cogging_dq_comp.372 0 -motor.cogging_dq_comp.373 0 -motor.cogging_dq_comp.374 0 -motor.cogging_dq_comp.375 0 -motor.cogging_dq_comp.376 0 -motor.cogging_dq_comp.377 0 -motor.cogging_dq_comp.378 0 -motor.cogging_dq_comp.379 0 -motor.cogging_dq_comp.380 0 -motor.cogging_dq_comp.381 0 -motor.cogging_dq_comp.382 0 -motor.cogging_dq_comp.383 0 -motor.cogging_dq_comp.384 0 -motor.cogging_dq_comp.385 0 -motor.cogging_dq_comp.386 0 -motor.cogging_dq_comp.387 0 -motor.cogging_dq_comp.388 0 -motor.cogging_dq_comp.389 0 -motor.cogging_dq_comp.390 0 -motor.cogging_dq_comp.391 0 -motor.cogging_dq_comp.392 0 -motor.cogging_dq_comp.393 0 -motor.cogging_dq_comp.394 0 -motor.cogging_dq_comp.395 0 -motor.cogging_dq_comp.396 0 -motor.cogging_dq_comp.397 0 -motor.cogging_dq_comp.398 0 -motor.cogging_dq_comp.399 0 -motor.cogging_dq_comp.400 0 -motor.cogging_dq_comp.401 0 -motor.cogging_dq_comp.402 0 -motor.cogging_dq_comp.403 0 -motor.cogging_dq_comp.404 0 -motor.cogging_dq_comp.405 0 -motor.cogging_dq_comp.406 0 -motor.cogging_dq_comp.407 0 -motor.cogging_dq_comp.408 0 -motor.cogging_dq_comp.409 0 -motor.cogging_dq_comp.410 0 -motor.cogging_dq_comp.411 0 -motor.cogging_dq_comp.412 0 -motor.cogging_dq_comp.413 0 -motor.cogging_dq_comp.414 0 -motor.cogging_dq_comp.415 0 -motor.cogging_dq_comp.416 0 -motor.cogging_dq_comp.417 0 -motor.cogging_dq_comp.418 0 -motor.cogging_dq_comp.419 0 -motor.cogging_dq_comp.420 0 -motor.cogging_dq_comp.421 0 -motor.cogging_dq_comp.422 0 -motor.cogging_dq_comp.423 0 -motor.cogging_dq_comp.424 0 -motor.cogging_dq_comp.425 0 -motor.cogging_dq_comp.426 0 -motor.cogging_dq_comp.427 0 -motor.cogging_dq_comp.428 0 -motor.cogging_dq_comp.429 0 -motor.cogging_dq_comp.430 0 -motor.cogging_dq_comp.431 0 -motor.cogging_dq_comp.432 0 -motor.cogging_dq_comp.433 0 -motor.cogging_dq_comp.434 0 -motor.cogging_dq_comp.435 0 -motor.cogging_dq_comp.436 0 -motor.cogging_dq_comp.437 0 -motor.cogging_dq_comp.438 0 -motor.cogging_dq_comp.439 0 -motor.cogging_dq_comp.440 0 -motor.cogging_dq_comp.441 0 -motor.cogging_dq_comp.442 0 -motor.cogging_dq_comp.443 0 -motor.cogging_dq_comp.444 0 -motor.cogging_dq_comp.445 0 -motor.cogging_dq_comp.446 0 -motor.cogging_dq_comp.447 0 -motor.cogging_dq_comp.448 0 -motor.cogging_dq_comp.449 0 -motor.cogging_dq_comp.450 0 -motor.cogging_dq_comp.451 0 -motor.cogging_dq_comp.452 0 -motor.cogging_dq_comp.453 0 -motor.cogging_dq_comp.454 0 -motor.cogging_dq_comp.455 0 -motor.cogging_dq_comp.456 0 -motor.cogging_dq_comp.457 0 -motor.cogging_dq_comp.458 0 -motor.cogging_dq_comp.459 0 -motor.cogging_dq_comp.460 0 -motor.cogging_dq_comp.461 0 -motor.cogging_dq_comp.462 0 -motor.cogging_dq_comp.463 0 -motor.cogging_dq_comp.464 0 -motor.cogging_dq_comp.465 0 -motor.cogging_dq_comp.466 0 -motor.cogging_dq_comp.467 0 -motor.cogging_dq_comp.468 0 -motor.cogging_dq_comp.469 0 -motor.cogging_dq_comp.470 0 -motor.cogging_dq_comp.471 0 -motor.cogging_dq_comp.472 0 -motor.cogging_dq_comp.473 0 -motor.cogging_dq_comp.474 0 -motor.cogging_dq_comp.475 0 -motor.cogging_dq_comp.476 0 -motor.cogging_dq_comp.477 0 -motor.cogging_dq_comp.478 0 -motor.cogging_dq_comp.479 0 -motor.cogging_dq_comp.480 0 -motor.cogging_dq_comp.481 0 -motor.cogging_dq_comp.482 0 -motor.cogging_dq_comp.483 0 -motor.cogging_dq_comp.484 0 -motor.cogging_dq_comp.485 0 -motor.cogging_dq_comp.486 0 -motor.cogging_dq_comp.487 0 -motor.cogging_dq_comp.488 0 -motor.cogging_dq_comp.489 0 -motor.cogging_dq_comp.490 0 -motor.cogging_dq_comp.491 0 -motor.cogging_dq_comp.492 0 -motor.cogging_dq_comp.493 0 -motor.cogging_dq_comp.494 0 -motor.cogging_dq_comp.495 0 -motor.cogging_dq_comp.496 0 -motor.cogging_dq_comp.497 0 -motor.cogging_dq_comp.498 0 -motor.cogging_dq_comp.499 0 -motor.cogging_dq_comp.500 0 -motor.cogging_dq_comp.501 0 -motor.cogging_dq_comp.502 0 -motor.cogging_dq_comp.503 0 -motor.cogging_dq_comp.504 0 -motor.cogging_dq_comp.505 0 -motor.cogging_dq_comp.506 0 -motor.cogging_dq_comp.507 0 -motor.cogging_dq_comp.508 0 -motor.cogging_dq_comp.509 0 -motor.cogging_dq_comp.510 0 -motor.cogging_dq_comp.511 0 -motor.cogging_dq_comp.512 0 -motor.cogging_dq_comp.513 0 -motor.cogging_dq_comp.514 0 -motor.cogging_dq_comp.515 0 -motor.cogging_dq_comp.516 0 -motor.cogging_dq_comp.517 0 -motor.cogging_dq_comp.518 0 -motor.cogging_dq_comp.519 0 -motor.cogging_dq_comp.520 0 -motor.cogging_dq_comp.521 0 -motor.cogging_dq_comp.522 0 -motor.cogging_dq_comp.523 0 -motor.cogging_dq_comp.524 0 -motor.cogging_dq_comp.525 0 -motor.cogging_dq_comp.526 0 -motor.cogging_dq_comp.527 0 -motor.cogging_dq_comp.528 0 -motor.cogging_dq_comp.529 0 -motor.cogging_dq_comp.530 0 -motor.cogging_dq_comp.531 0 -motor.cogging_dq_comp.532 0 -motor.cogging_dq_comp.533 0 -motor.cogging_dq_comp.534 0 -motor.cogging_dq_comp.535 0 -motor.cogging_dq_comp.536 0 -motor.cogging_dq_comp.537 0 -motor.cogging_dq_comp.538 0 -motor.cogging_dq_comp.539 0 -motor.cogging_dq_comp.540 0 -motor.cogging_dq_comp.541 0 -motor.cogging_dq_comp.542 0 -motor.cogging_dq_comp.543 0 -motor.cogging_dq_comp.544 0 -motor.cogging_dq_comp.545 0 -motor.cogging_dq_comp.546 0 -motor.cogging_dq_comp.547 0 -motor.cogging_dq_comp.548 0 -motor.cogging_dq_comp.549 0 -motor.cogging_dq_comp.550 0 -motor.cogging_dq_comp.551 0 -motor.cogging_dq_comp.552 0 -motor.cogging_dq_comp.553 0 -motor.cogging_dq_comp.554 0 -motor.cogging_dq_comp.555 0 -motor.cogging_dq_comp.556 0 -motor.cogging_dq_comp.557 0 -motor.cogging_dq_comp.558 0 -motor.cogging_dq_comp.559 0 -motor.cogging_dq_comp.560 0 -motor.cogging_dq_comp.561 0 -motor.cogging_dq_comp.562 0 -motor.cogging_dq_comp.563 0 -motor.cogging_dq_comp.564 0 -motor.cogging_dq_comp.565 0 -motor.cogging_dq_comp.566 0 -motor.cogging_dq_comp.567 0 -motor.cogging_dq_comp.568 0 -motor.cogging_dq_comp.569 0 -motor.cogging_dq_comp.570 0 -motor.cogging_dq_comp.571 0 -motor.cogging_dq_comp.572 0 -motor.cogging_dq_comp.573 0 -motor.cogging_dq_comp.574 0 -motor.cogging_dq_comp.575 0 -motor.cogging_dq_comp.576 0 -motor.cogging_dq_comp.577 0 -motor.cogging_dq_comp.578 0 -motor.cogging_dq_comp.579 0 -motor.cogging_dq_comp.580 0 -motor.cogging_dq_comp.581 0 -motor.cogging_dq_comp.582 0 -motor.cogging_dq_comp.583 0 -motor.cogging_dq_comp.584 0 -motor.cogging_dq_comp.585 0 -motor.cogging_dq_comp.586 0 -motor.cogging_dq_comp.587 0 -motor.cogging_dq_comp.588 0 -motor.cogging_dq_comp.589 0 -motor.cogging_dq_comp.590 0 -motor.cogging_dq_comp.591 0 -motor.cogging_dq_comp.592 0 -motor.cogging_dq_comp.593 0 -motor.cogging_dq_comp.594 0 -motor.cogging_dq_comp.595 0 -motor.cogging_dq_comp.596 0 -motor.cogging_dq_comp.597 0 -motor.cogging_dq_comp.598 0 -motor.cogging_dq_comp.599 0 -motor.cogging_dq_comp.600 0 -motor.cogging_dq_comp.601 0 -motor.cogging_dq_comp.602 0 -motor.cogging_dq_comp.603 0 -motor.cogging_dq_comp.604 0 -motor.cogging_dq_comp.605 0 -motor.cogging_dq_comp.606 0 -motor.cogging_dq_comp.607 0 -motor.cogging_dq_comp.608 0 -motor.cogging_dq_comp.609 0 -motor.cogging_dq_comp.610 0 -motor.cogging_dq_comp.611 0 -motor.cogging_dq_comp.612 0 -motor.cogging_dq_comp.613 0 -motor.cogging_dq_comp.614 0 -motor.cogging_dq_comp.615 0 -motor.cogging_dq_comp.616 0 -motor.cogging_dq_comp.617 0 -motor.cogging_dq_comp.618 0 -motor.cogging_dq_comp.619 0 -motor.cogging_dq_comp.620 0 -motor.cogging_dq_comp.621 0 -motor.cogging_dq_comp.622 0 -motor.cogging_dq_comp.623 0 -motor.cogging_dq_comp.624 0 -motor.cogging_dq_comp.625 0 -motor.cogging_dq_comp.626 0 -motor.cogging_dq_comp.627 0 -motor.cogging_dq_comp.628 0 -motor.cogging_dq_comp.629 0 -motor.cogging_dq_comp.630 0 -motor.cogging_dq_comp.631 0 -motor.cogging_dq_comp.632 0 -motor.cogging_dq_comp.633 0 -motor.cogging_dq_comp.634 0 -motor.cogging_dq_comp.635 0 -motor.cogging_dq_comp.636 0 -motor.cogging_dq_comp.637 0 -motor.cogging_dq_comp.638 0 -motor.cogging_dq_comp.639 0 -motor.cogging_dq_comp.640 0 -motor.cogging_dq_comp.641 0 -motor.cogging_dq_comp.642 0 -motor.cogging_dq_comp.643 0 -motor.cogging_dq_comp.644 0 -motor.cogging_dq_comp.645 0 -motor.cogging_dq_comp.646 0 -motor.cogging_dq_comp.647 0 -motor.cogging_dq_comp.648 0 -motor.cogging_dq_comp.649 0 -motor.cogging_dq_comp.650 0 -motor.cogging_dq_comp.651 0 -motor.cogging_dq_comp.652 0 -motor.cogging_dq_comp.653 0 -motor.cogging_dq_comp.654 0 -motor.cogging_dq_comp.655 0 -motor.cogging_dq_comp.656 0 -motor.cogging_dq_comp.657 0 -motor.cogging_dq_comp.658 0 -motor.cogging_dq_comp.659 0 -motor.cogging_dq_comp.660 0 -motor.cogging_dq_comp.661 0 -motor.cogging_dq_comp.662 0 -motor.cogging_dq_comp.663 0 -motor.cogging_dq_comp.664 0 -motor.cogging_dq_comp.665 0 -motor.cogging_dq_comp.666 0 -motor.cogging_dq_comp.667 0 -motor.cogging_dq_comp.668 0 -motor.cogging_dq_comp.669 0 -motor.cogging_dq_comp.670 0 -motor.cogging_dq_comp.671 0 -motor.cogging_dq_comp.672 0 -motor.cogging_dq_comp.673 0 -motor.cogging_dq_comp.674 0 -motor.cogging_dq_comp.675 0 -motor.cogging_dq_comp.676 0 -motor.cogging_dq_comp.677 0 -motor.cogging_dq_comp.678 0 -motor.cogging_dq_comp.679 0 -motor.cogging_dq_comp.680 0 -motor.cogging_dq_comp.681 0 -motor.cogging_dq_comp.682 0 -motor.cogging_dq_comp.683 0 -motor.cogging_dq_comp.684 0 -motor.cogging_dq_comp.685 0 -motor.cogging_dq_comp.686 0 -motor.cogging_dq_comp.687 0 -motor.cogging_dq_comp.688 0 -motor.cogging_dq_comp.689 0 -motor.cogging_dq_comp.690 0 -motor.cogging_dq_comp.691 0 -motor.cogging_dq_comp.692 0 -motor.cogging_dq_comp.693 0 -motor.cogging_dq_comp.694 0 -motor.cogging_dq_comp.695 0 -motor.cogging_dq_comp.696 0 -motor.cogging_dq_comp.697 0 -motor.cogging_dq_comp.698 0 -motor.cogging_dq_comp.699 0 -motor.cogging_dq_comp.700 0 -motor.cogging_dq_comp.701 0 -motor.cogging_dq_comp.702 0 -motor.cogging_dq_comp.703 0 -motor.cogging_dq_comp.704 0 -motor.cogging_dq_comp.705 0 -motor.cogging_dq_comp.706 0 -motor.cogging_dq_comp.707 0 -motor.cogging_dq_comp.708 0 -motor.cogging_dq_comp.709 0 -motor.cogging_dq_comp.710 0 -motor.cogging_dq_comp.711 0 -motor.cogging_dq_comp.712 0 -motor.cogging_dq_comp.713 0 -motor.cogging_dq_comp.714 0 -motor.cogging_dq_comp.715 0 -motor.cogging_dq_comp.716 0 -motor.cogging_dq_comp.717 0 -motor.cogging_dq_comp.718 0 -motor.cogging_dq_comp.719 0 -motor.cogging_dq_comp.720 0 -motor.cogging_dq_comp.721 0 -motor.cogging_dq_comp.722 0 -motor.cogging_dq_comp.723 0 -motor.cogging_dq_comp.724 0 -motor.cogging_dq_comp.725 0 -motor.cogging_dq_comp.726 0 -motor.cogging_dq_comp.727 0 -motor.cogging_dq_comp.728 0 -motor.cogging_dq_comp.729 0 -motor.cogging_dq_comp.730 0 -motor.cogging_dq_comp.731 0 -motor.cogging_dq_comp.732 0 -motor.cogging_dq_comp.733 0 -motor.cogging_dq_comp.734 0 -motor.cogging_dq_comp.735 0 -motor.cogging_dq_comp.736 0 -motor.cogging_dq_comp.737 0 -motor.cogging_dq_comp.738 0 -motor.cogging_dq_comp.739 0 -motor.cogging_dq_comp.740 0 -motor.cogging_dq_comp.741 0 -motor.cogging_dq_comp.742 0 -motor.cogging_dq_comp.743 0 -motor.cogging_dq_comp.744 0 -motor.cogging_dq_comp.745 0 -motor.cogging_dq_comp.746 0 -motor.cogging_dq_comp.747 0 -motor.cogging_dq_comp.748 0 -motor.cogging_dq_comp.749 0 -motor.cogging_dq_comp.750 0 -motor.cogging_dq_comp.751 0 -motor.cogging_dq_comp.752 0 -motor.cogging_dq_comp.753 0 -motor.cogging_dq_comp.754 0 -motor.cogging_dq_comp.755 0 -motor.cogging_dq_comp.756 0 -motor.cogging_dq_comp.757 0 -motor.cogging_dq_comp.758 0 -motor.cogging_dq_comp.759 0 -motor.cogging_dq_comp.760 0 -motor.cogging_dq_comp.761 0 -motor.cogging_dq_comp.762 0 -motor.cogging_dq_comp.763 0 -motor.cogging_dq_comp.764 0 -motor.cogging_dq_comp.765 0 -motor.cogging_dq_comp.766 0 -motor.cogging_dq_comp.767 0 -motor.cogging_dq_comp.768 0 -motor.cogging_dq_comp.769 0 -motor.cogging_dq_comp.770 0 -motor.cogging_dq_comp.771 0 -motor.cogging_dq_comp.772 0 -motor.cogging_dq_comp.773 0 -motor.cogging_dq_comp.774 0 -motor.cogging_dq_comp.775 0 -motor.cogging_dq_comp.776 0 -motor.cogging_dq_comp.777 0 -motor.cogging_dq_comp.778 0 -motor.cogging_dq_comp.779 0 -motor.cogging_dq_comp.780 0 -motor.cogging_dq_comp.781 0 -motor.cogging_dq_comp.782 0 -motor.cogging_dq_comp.783 0 -motor.cogging_dq_comp.784 0 -motor.cogging_dq_comp.785 0 -motor.cogging_dq_comp.786 0 -motor.cogging_dq_comp.787 0 -motor.cogging_dq_comp.788 0 -motor.cogging_dq_comp.789 0 -motor.cogging_dq_comp.790 0 -motor.cogging_dq_comp.791 0 -motor.cogging_dq_comp.792 0 -motor.cogging_dq_comp.793 0 -motor.cogging_dq_comp.794 0 -motor.cogging_dq_comp.795 0 -motor.cogging_dq_comp.796 0 -motor.cogging_dq_comp.797 0 -motor.cogging_dq_comp.798 0 -motor.cogging_dq_comp.799 0 -motor.cogging_dq_comp.800 0 -motor.cogging_dq_comp.801 0 -motor.cogging_dq_comp.802 0 -motor.cogging_dq_comp.803 0 -motor.cogging_dq_comp.804 0 -motor.cogging_dq_comp.805 0 -motor.cogging_dq_comp.806 0 -motor.cogging_dq_comp.807 0 -motor.cogging_dq_comp.808 0 -motor.cogging_dq_comp.809 0 -motor.cogging_dq_comp.810 0 -motor.cogging_dq_comp.811 0 -motor.cogging_dq_comp.812 0 -motor.cogging_dq_comp.813 0 -motor.cogging_dq_comp.814 0 -motor.cogging_dq_comp.815 0 -motor.cogging_dq_comp.816 0 -motor.cogging_dq_comp.817 0 -motor.cogging_dq_comp.818 0 -motor.cogging_dq_comp.819 0 -motor.cogging_dq_comp.820 0 -motor.cogging_dq_comp.821 0 -motor.cogging_dq_comp.822 0 -motor.cogging_dq_comp.823 0 -motor.cogging_dq_comp.824 0 -motor.cogging_dq_comp.825 0 -motor.cogging_dq_comp.826 0 -motor.cogging_dq_comp.827 0 -motor.cogging_dq_comp.828 0 -motor.cogging_dq_comp.829 0 -motor.cogging_dq_comp.830 0 -motor.cogging_dq_comp.831 0 -motor.cogging_dq_comp.832 0 -motor.cogging_dq_comp.833 0 -motor.cogging_dq_comp.834 0 -motor.cogging_dq_comp.835 0 -motor.cogging_dq_comp.836 0 -motor.cogging_dq_comp.837 0 -motor.cogging_dq_comp.838 0 -motor.cogging_dq_comp.839 0 -motor.cogging_dq_comp.840 0 -motor.cogging_dq_comp.841 0 -motor.cogging_dq_comp.842 0 -motor.cogging_dq_comp.843 0 -motor.cogging_dq_comp.844 0 -motor.cogging_dq_comp.845 0 -motor.cogging_dq_comp.846 0 -motor.cogging_dq_comp.847 0 -motor.cogging_dq_comp.848 0 -motor.cogging_dq_comp.849 0 -motor.cogging_dq_comp.850 0 -motor.cogging_dq_comp.851 0 -motor.cogging_dq_comp.852 0 -motor.cogging_dq_comp.853 0 -motor.cogging_dq_comp.854 0 -motor.cogging_dq_comp.855 0 -motor.cogging_dq_comp.856 0 -motor.cogging_dq_comp.857 0 -motor.cogging_dq_comp.858 0 -motor.cogging_dq_comp.859 0 -motor.cogging_dq_comp.860 0 -motor.cogging_dq_comp.861 0 -motor.cogging_dq_comp.862 0 -motor.cogging_dq_comp.863 0 -motor.cogging_dq_comp.864 0 -motor.cogging_dq_comp.865 0 -motor.cogging_dq_comp.866 0 -motor.cogging_dq_comp.867 0 -motor.cogging_dq_comp.868 0 -motor.cogging_dq_comp.869 0 -motor.cogging_dq_comp.870 0 -motor.cogging_dq_comp.871 0 -motor.cogging_dq_comp.872 0 -motor.cogging_dq_comp.873 0 -motor.cogging_dq_comp.874 0 -motor.cogging_dq_comp.875 0 -motor.cogging_dq_comp.876 0 -motor.cogging_dq_comp.877 0 -motor.cogging_dq_comp.878 0 -motor.cogging_dq_comp.879 0 -motor.cogging_dq_comp.880 0 -motor.cogging_dq_comp.881 0 -motor.cogging_dq_comp.882 0 -motor.cogging_dq_comp.883 0 -motor.cogging_dq_comp.884 0 -motor.cogging_dq_comp.885 0 -motor.cogging_dq_comp.886 0 -motor.cogging_dq_comp.887 0 -motor.cogging_dq_comp.888 0 -motor.cogging_dq_comp.889 0 -motor.cogging_dq_comp.890 0 -motor.cogging_dq_comp.891 0 -motor.cogging_dq_comp.892 0 -motor.cogging_dq_comp.893 0 -motor.cogging_dq_comp.894 0 -motor.cogging_dq_comp.895 0 -motor.cogging_dq_comp.896 0 -motor.cogging_dq_comp.897 0 -motor.cogging_dq_comp.898 0 -motor.cogging_dq_comp.899 0 -motor.cogging_dq_comp.900 0 -motor.cogging_dq_comp.901 0 -motor.cogging_dq_comp.902 0 -motor.cogging_dq_comp.903 0 -motor.cogging_dq_comp.904 0 -motor.cogging_dq_comp.905 0 -motor.cogging_dq_comp.906 0 -motor.cogging_dq_comp.907 0 -motor.cogging_dq_comp.908 0 -motor.cogging_dq_comp.909 0 -motor.cogging_dq_comp.910 0 -motor.cogging_dq_comp.911 0 -motor.cogging_dq_comp.912 0 -motor.cogging_dq_comp.913 0 -motor.cogging_dq_comp.914 0 -motor.cogging_dq_comp.915 0 -motor.cogging_dq_comp.916 0 -motor.cogging_dq_comp.917 0 -motor.cogging_dq_comp.918 0 -motor.cogging_dq_comp.919 0 -motor.cogging_dq_comp.920 0 -motor.cogging_dq_comp.921 0 -motor.cogging_dq_comp.922 0 -motor.cogging_dq_comp.923 0 -motor.cogging_dq_comp.924 0 -motor.cogging_dq_comp.925 0 -motor.cogging_dq_comp.926 0 -motor.cogging_dq_comp.927 0 -motor.cogging_dq_comp.928 0 -motor.cogging_dq_comp.929 0 -motor.cogging_dq_comp.930 0 -motor.cogging_dq_comp.931 0 -motor.cogging_dq_comp.932 0 -motor.cogging_dq_comp.933 0 -motor.cogging_dq_comp.934 0 -motor.cogging_dq_comp.935 0 -motor.cogging_dq_comp.936 0 -motor.cogging_dq_comp.937 0 -motor.cogging_dq_comp.938 0 -motor.cogging_dq_comp.939 0 -motor.cogging_dq_comp.940 0 -motor.cogging_dq_comp.941 0 -motor.cogging_dq_comp.942 0 -motor.cogging_dq_comp.943 0 -motor.cogging_dq_comp.944 0 -motor.cogging_dq_comp.945 0 -motor.cogging_dq_comp.946 0 -motor.cogging_dq_comp.947 0 -motor.cogging_dq_comp.948 0 -motor.cogging_dq_comp.949 0 -motor.cogging_dq_comp.950 0 -motor.cogging_dq_comp.951 0 -motor.cogging_dq_comp.952 0 -motor.cogging_dq_comp.953 0 -motor.cogging_dq_comp.954 0 -motor.cogging_dq_comp.955 0 -motor.cogging_dq_comp.956 0 -motor.cogging_dq_comp.957 0 -motor.cogging_dq_comp.958 0 -motor.cogging_dq_comp.959 0 -motor.cogging_dq_comp.960 0 -motor.cogging_dq_comp.961 0 -motor.cogging_dq_comp.962 0 -motor.cogging_dq_comp.963 0 -motor.cogging_dq_comp.964 0 -motor.cogging_dq_comp.965 0 -motor.cogging_dq_comp.966 0 -motor.cogging_dq_comp.967 0 -motor.cogging_dq_comp.968 0 -motor.cogging_dq_comp.969 0 -motor.cogging_dq_comp.970 0 -motor.cogging_dq_comp.971 0 -motor.cogging_dq_comp.972 0 -motor.cogging_dq_comp.973 0 -motor.cogging_dq_comp.974 0 -motor.cogging_dq_comp.975 0 -motor.cogging_dq_comp.976 0 -motor.cogging_dq_comp.977 0 -motor.cogging_dq_comp.978 0 -motor.cogging_dq_comp.979 0 -motor.cogging_dq_comp.980 0 -motor.cogging_dq_comp.981 0 -motor.cogging_dq_comp.982 0 -motor.cogging_dq_comp.983 0 -motor.cogging_dq_comp.984 0 -motor.cogging_dq_comp.985 0 -motor.cogging_dq_comp.986 0 -motor.cogging_dq_comp.987 0 -motor.cogging_dq_comp.988 0 -motor.cogging_dq_comp.989 0 -motor.cogging_dq_comp.990 0 -motor.cogging_dq_comp.991 0 -motor.cogging_dq_comp.992 0 -motor.cogging_dq_comp.993 0 -motor.cogging_dq_comp.994 0 -motor.cogging_dq_comp.995 0 -motor.cogging_dq_comp.996 0 -motor.cogging_dq_comp.997 0 -motor.cogging_dq_comp.998 0 -motor.cogging_dq_comp.999 0 -motor.cogging_dq_comp.1000 0 -motor.cogging_dq_comp.1001 0 -motor.cogging_dq_comp.1002 0 -motor.cogging_dq_comp.1003 0 -motor.cogging_dq_comp.1004 0 -motor.cogging_dq_comp.1005 0 -motor.cogging_dq_comp.1006 0 -motor.cogging_dq_comp.1007 0 -motor.cogging_dq_comp.1008 0 -motor.cogging_dq_comp.1009 0 -motor.cogging_dq_comp.1010 0 -motor.cogging_dq_comp.1011 0 -motor.cogging_dq_comp.1012 0 -motor.cogging_dq_comp.1013 0 -motor.cogging_dq_comp.1014 0 -motor.cogging_dq_comp.1015 0 -motor.cogging_dq_comp.1016 0 -motor.cogging_dq_comp.1017 0 -motor.cogging_dq_comp.1018 0 -motor.cogging_dq_comp.1019 0 -motor.cogging_dq_comp.1020 0 -motor.cogging_dq_comp.1021 0 -motor.cogging_dq_comp.1022 0 -motor.cogging_dq_comp.1023 0 -drv8323_conf.dis_cpuv 0 -drv8323_conf.dis_gdf 0 -drv8323_conf.otw_rep 0 -drv8323_conf.pwm_mode 1 -drv8323_conf.pwm_1x_asynchronous 0 -drv8323_conf.pwm_1x_dir 0 -drv8323_conf.idrivep_hs_ma 150 -drv8323_conf.idriven_hs_ma 300 -drv8323_conf.cbc 1 -drv8323_conf.tdrive_ns 1000 -drv8323_conf.idrivep_ls_ma 150 -drv8323_conf.idriven_ls_ma 300 -drv8323_conf.tretry 0 -drv8323_conf.dead_time_ns 50 -drv8323_conf.ocp_mode 0 -drv8323_conf.ocp_deg_us 4 -drv8323_conf.vds_lvl_mv 700 -drv8323_conf.csa_fet 0 -drv8323_conf.vref_div 1 -drv8323_conf.ls_ref 0 -drv8323_conf.csa_gain 20 -drv8323_conf.dis_sen 0 -drv8323_conf.sen_lvl_mv 500 -servo.pwm_rate_hz 30000 -servo.i_gain 20.000000 -servo.current_sense_ohm 0.000500 -servo.pwm_comp_off 0.027000 -servo.pwm_comp_mag 0.005000 -servo.pwm_scale 1.000000 -servo.max_voltage 56.000000 -servo.max_power_W 450.000000 -servo.derate_temperature 50.000000 -servo.fault_temperature 75.000000 -servo.enable_motor_temperature 0 -servo.motor_derate_temperature 50.000000 -servo.motor_fault_temperature nan -servo.velocity_threshold 0.000000 -servo.position_derate 0.020000 -servo.adc_cur_cycles 2 -servo.adc_aux_cycles 47 -servo.pid_dq.kp 1.572669 -servo.pid_dq.ki 1652.041870 -servo.pid_position.kp 0.950000 -servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.100000 -servo.pid_position.iratelimit -1.000000 -servo.pid_position.ilimit 0.000000 -servo.pid_position.max_desired_rate 0.000000 -servo.pid_position.sign -1 -servo.current_feedforward 1.000000 -servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit nan -servo.voltage_mode_control 0 -servo.fixed_voltage_mode 0 -servo.fixed_voltage_control_V 0.000000 -servo.max_position_slip 15.000000 -servo.max_velocity_slip nan -servo.default_timeout_s 0.100000 -servo.timeout_max_torque_Nm 5.000000 -servo.timeout_mode 12 -servo.flux_brake_min_voltage 53.000000 -servo.flux_brake_resistance_ohm 0.025000 -servo.max_current_A 100.000000 -servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 -servo.max_velocity_derate 2.000000 -servo.cooldown_cycles 256 -servo.velocity_zero_capture_threshold 0.050000 -servo.timing_fault 0 -servo.emit_debug 0 -servopos.position_min nan -servopos.position_max nan -id.id 36 -can.prefix 0 - diff --git a/config/moteus/a/pid_no_load.config b/config/moteus/joint_a.cfg similarity index 98% rename from config/moteus/a/pid_no_load.config rename to config/moteus/joint_a.cfg index 438366ef0..aaab74389 100644 --- a/config/moteus/a/pid_no_load.config +++ b/config/moteus/joint_a.cfg @@ -1,19 +1,19 @@ -uuid.uuid.0 26 -uuid.uuid.1 252 -uuid.uuid.2 31 -uuid.uuid.3 59 -uuid.uuid.4 74 -uuid.uuid.5 28 -uuid.uuid.6 78 -uuid.uuid.7 47 -uuid.uuid.8 176 -uuid.uuid.9 23 -uuid.uuid.10 152 -uuid.uuid.11 23 -uuid.uuid.12 70 -uuid.uuid.13 18 -uuid.uuid.14 56 -uuid.uuid.15 20 +uuid.uuid.0 55 +uuid.uuid.1 182 +uuid.uuid.2 228 +uuid.uuid.3 110 +uuid.uuid.4 120 +uuid.uuid.5 156 +uuid.uuid.6 75 +uuid.uuid.7 137 +uuid.uuid.8 129 +uuid.uuid.9 230 +uuid.uuid.10 178 +uuid.uuid.11 201 +uuid.uuid.12 154 +uuid.uuid.13 163 +uuid.uuid.14 21 +uuid.uuid.15 188 clock.hsitrim 64 aux1.i2c.i2c_hz 400000 aux1.i2c.i2c_mode 1 @@ -83,10 +83,10 @@ aux2.index.enabled 0 aux2.sine_cosine.enabled 0 aux2.sine_cosine.common 1700 aux2.i2c_startup_delay_ms 30 -aux2.pins.0.mode 0 -aux2.pins.0.pull 0 -aux2.pins.1.mode 0 -aux2.pins.1.pull 0 +aux2.pins.0.mode 14 +aux2.pins.0.pull 1 +aux2.pins.1.mode 14 +aux2.pins.1.pull 1 aux2.pins.2.mode 0 aux2.pins.2.pull 0 aux2.pins.3.mode 0 @@ -98,7 +98,7 @@ motor_position.sources.0.type 4 motor_position.sources.0.i2c_device 0 motor_position.sources.0.incremental_index -1 motor_position.sources.0.cpr 42 -motor_position.sources.0.offset -1.000000 +motor_position.sources.0.offset -5.000000 motor_position.sources.0.sign -1 motor_position.sources.0.debug_override -1 motor_position.sources.0.reference 0 @@ -224,11 +224,11 @@ motor_position.output.source 0 motor_position.output.offset 0.000000 motor_position.output.sign 1 motor_position.output.reference_source -1 -motor_position.rotor_to_output_ratio 1.000000 +motor_position.rotor_to_output_ratio 0.005080 motor.poles 14 motor.phase_invert 0 -motor.resistance_ohm 0.162091 -motor.v_per_hz 0.351471 +motor.resistance_ohm 0.160509 +motor.v_per_hz 0.132894 motor.offset.0 0.000000 motor.offset.1 0.000000 motor.offset.2 0.000000 @@ -1361,19 +1361,19 @@ servo.velocity_threshold 0.000000 servo.position_derate 0.020000 servo.adc_cur_cycles 2 servo.adc_aux_cycles 47 -servo.pid_dq.kp 0.117592 -servo.pid_dq.ki 203.689606 -servo.pid_position.kp 0.003000 +servo.pid_dq.kp 0.060857 +servo.pid_dq.ki 100.850487 +servo.pid_position.kp 3000.000000 servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.000200 +servo.pid_position.kd 200.000000 servo.pid_position.iratelimit -1.000000 servo.pid_position.ilimit 0.000000 servo.pid_position.max_desired_rate 0.000000 servo.pid_position.sign -1 servo.current_feedforward 1.000000 servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit 5.000000 +servo.default_velocity_limit 0.150000 +servo.default_accel_limit 0.300000 servo.voltage_mode_control 0 servo.fixed_voltage_mode 0 servo.fixed_voltage_control_V 0.000000 @@ -1386,7 +1386,7 @@ servo.flux_brake_min_voltage 43.500000 servo.flux_brake_resistance_ohm 0.025000 servo.max_current_A 100.000000 servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 +servo.max_velocity 0.180000 servo.max_velocity_derate 2.000000 servo.cooldown_cycles 256 servo.velocity_zero_capture_threshold 0.050000 diff --git a/config/moteus/jointC.cfg b/config/moteus/joint_c.cfg similarity index 99% rename from config/moteus/jointC.cfg rename to config/moteus/joint_c.cfg index 21075d8a2..c475f8708 100644 --- a/config/moteus/jointC.cfg +++ b/config/moteus/joint_c.cfg @@ -139,7 +139,7 @@ motor_position.sources.1.aux_number 1 motor_position.sources.1.type 7 motor_position.sources.1.i2c_device 0 motor_position.sources.1.incremental_index -1 -motor_position.sources.1.cpr 16384 +motor_position.sources.1.cpr 65536 motor_position.sources.1.offset 0.000000 motor_position.sources.1.sign -1 motor_position.sources.1.debug_override -1 @@ -221,7 +221,7 @@ motor_position.sources.2.compensation_table.30 0.000000 motor_position.sources.2.compensation_table.31 0.000000 motor_position.commutation_source 0 motor_position.output.source 0 -motor_position.output.offset 0.730000 +motor_position.output.offset 0.297363 motor_position.output.sign 1 motor_position.output.reference_source 1 motor_position.rotor_to_output_ratio 0.002066 @@ -1363,7 +1363,7 @@ servo.adc_cur_cycles 2 servo.adc_aux_cycles 47 servo.pid_dq.kp 0.060606 servo.pid_dq.ki 102.321388 -servo.pid_position.kp 7.000000 +servo.pid_position.kp 14.000000 servo.pid_position.ki 0.000000 servo.pid_position.kd 1.450000 servo.pid_position.iratelimit -1.000000 @@ -1372,8 +1372,8 @@ servo.pid_position.max_desired_rate 0.000000 servo.pid_position.sign -1 servo.current_feedforward 1.000000 servo.bemf_feedforward 1.000000 -servo.default_velocity_limit 100.000000 -servo.default_accel_limit 10.000000 +servo.default_velocity_limit 0.080000 +servo.default_accel_limit 0.200000 servo.voltage_mode_control 0 servo.fixed_voltage_mode 0 servo.fixed_voltage_control_V 0.000000 @@ -1385,7 +1385,7 @@ servo.flux_brake_min_voltage 53.000000 servo.flux_brake_resistance_ohm 0.025000 servo.max_current_A 100.000000 servo.derate_current_A -20.000000 -servo.max_velocity 100.000000 +servo.max_velocity 0.100000 servo.max_velocity_derate 2.000000 servo.cooldown_cycles 256 servo.velocity_zero_capture_threshold 0.050000 diff --git a/config/moteus/de0/pid_no_load.config b/config/moteus/joint_de_0.cfg similarity index 98% rename from config/moteus/de0/pid_no_load.config rename to config/moteus/joint_de_0.cfg index 45e3e5897..c116946d8 100644 --- a/config/moteus/de0/pid_no_load.config +++ b/config/moteus/joint_de_0.cfg @@ -17,8 +17,8 @@ uuid.uuid.15 144 clock.hsitrim 64 aux1.i2c.i2c_hz 400000 aux1.i2c.i2c_mode 1 -aux1.i2c.pullup 0 -aux1.i2c.devices.0.type 0 +aux1.i2c.pullup 1 +aux1.i2c.devices.0.type 1 aux1.i2c.devices.0.address 64 aux1.i2c.devices.0.poll_rate_us 1000 aux1.i2c.devices.1.type 0 @@ -50,10 +50,10 @@ aux1.pins.1.mode 0 aux1.pins.1.pull 0 aux1.pins.2.mode 0 aux1.pins.2.pull 0 -aux1.pins.3.mode 0 -aux1.pins.3.pull 0 -aux1.pins.4.mode 0 -aux1.pins.4.pull 0 +aux1.pins.3.mode 13 +aux1.pins.3.pull 1 +aux1.pins.4.mode 13 +aux1.pins.4.pull 1 aux2.i2c.i2c_hz 400000 aux2.i2c.i2c_mode 1 aux2.i2c.pullup 0 @@ -136,15 +136,15 @@ motor_position.sources.0.compensation_table.29 0.000000 motor_position.sources.0.compensation_table.30 0.000000 motor_position.sources.0.compensation_table.31 0.000000 motor_position.sources.1.aux_number 1 -motor_position.sources.1.type 0 +motor_position.sources.1.type 7 motor_position.sources.1.i2c_device 0 motor_position.sources.1.incremental_index -1 -motor_position.sources.1.cpr 16384 -motor_position.sources.1.offset 0.000000 +motor_position.sources.1.cpr 65536 +motor_position.sources.1.offset -34783.000000 motor_position.sources.1.sign 1 motor_position.sources.1.debug_override -1 motor_position.sources.1.reference 0 -motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.pll_filter_hz 100.000000 motor_position.sources.1.compensation_table.0 0.000000 motor_position.sources.1.compensation_table.1 0.000000 motor_position.sources.1.compensation_table.2 0.000000 @@ -227,8 +227,8 @@ motor_position.output.reference_source -1 motor_position.rotor_to_output_ratio 1.000000 motor.poles 16 motor.phase_invert 0 -motor.resistance_ohm 4.383775 -motor.v_per_hz 0.578135 +motor.resistance_ohm 3.711431 +motor.v_per_hz 0.576525 motor.offset.0 0.000000 motor.offset.1 0.000000 motor.offset.2 0.000000 @@ -1361,19 +1361,19 @@ servo.velocity_threshold 0.000000 servo.position_derate 0.020000 servo.adc_cur_cycles 2 servo.adc_aux_cycles 47 -servo.pid_dq.kp 2.768091 -servo.pid_dq.ki 5508.813477 -servo.pid_position.kp 0.160000 +servo.pid_dq.kp 1.387107 +servo.pid_dq.ki 2331.960449 +servo.pid_position.kp 1.300000 servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.004500 +servo.pid_position.kd 0.010000 servo.pid_position.iratelimit -1.000000 servo.pid_position.ilimit 0.000000 servo.pid_position.max_desired_rate 0.000000 servo.pid_position.sign -1 servo.current_feedforward 1.000000 servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit nan +servo.default_velocity_limit 5.000000 +servo.default_accel_limit 10.000000 servo.voltage_mode_control 0 servo.fixed_voltage_mode 0 servo.fixed_voltage_control_V 0.000000 @@ -1386,7 +1386,7 @@ servo.flux_brake_min_voltage 53.000000 servo.flux_brake_resistance_ohm 0.025000 servo.max_current_A 5.000000 servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 +servo.max_velocity 10.000000 servo.max_velocity_derate 2.000000 servo.cooldown_cycles 256 servo.velocity_zero_capture_threshold 0.050000 diff --git a/config/moteus/jointDE1.cfg b/config/moteus/joint_de_1.cfg similarity index 98% rename from config/moteus/jointDE1.cfg rename to config/moteus/joint_de_1.cfg index 4ca990e9b..68c5e7f78 100644 --- a/config/moteus/jointDE1.cfg +++ b/config/moteus/joint_de_1.cfg @@ -17,8 +17,8 @@ uuid.uuid.15 194 clock.hsitrim 64 aux1.i2c.i2c_hz 400000 aux1.i2c.i2c_mode 1 -aux1.i2c.pullup 0 -aux1.i2c.devices.0.type 0 +aux1.i2c.pullup 1 +aux1.i2c.devices.0.type 1 aux1.i2c.devices.0.address 64 aux1.i2c.devices.0.poll_rate_us 1000 aux1.i2c.devices.1.type 0 @@ -50,10 +50,10 @@ aux1.pins.1.mode 0 aux1.pins.1.pull 0 aux1.pins.2.mode 0 aux1.pins.2.pull 0 -aux1.pins.3.mode 0 -aux1.pins.3.pull 0 -aux1.pins.4.mode 0 -aux1.pins.4.pull 0 +aux1.pins.3.mode 13 +aux1.pins.3.pull 1 +aux1.pins.4.mode 13 +aux1.pins.4.pull 1 aux2.i2c.i2c_hz 400000 aux2.i2c.i2c_mode 1 aux2.i2c.pullup 0 @@ -136,15 +136,15 @@ motor_position.sources.0.compensation_table.29 0.000000 motor_position.sources.0.compensation_table.30 0.000000 motor_position.sources.0.compensation_table.31 0.000000 motor_position.sources.1.aux_number 1 -motor_position.sources.1.type 0 +motor_position.sources.1.type 7 motor_position.sources.1.i2c_device 0 motor_position.sources.1.incremental_index -1 -motor_position.sources.1.cpr 16384 -motor_position.sources.1.offset 0.000000 +motor_position.sources.1.cpr 65536 +motor_position.sources.1.offset -52120.000000 motor_position.sources.1.sign 1 motor_position.sources.1.debug_override -1 -motor_position.sources.1.reference 0 -motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.reference 1 +motor_position.sources.1.pll_filter_hz 100.000000 motor_position.sources.1.compensation_table.0 0.000000 motor_position.sources.1.compensation_table.1 0.000000 motor_position.sources.1.compensation_table.2 0.000000 @@ -1363,17 +1363,17 @@ servo.adc_cur_cycles 2 servo.adc_aux_cycles 47 servo.pid_dq.kp 3.135870 servo.pid_dq.ki 4214.477539 -servo.pid_position.kp 0.160000 +servo.pid_position.kp 0.900000 servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.004500 +servo.pid_position.kd 0.085000 servo.pid_position.iratelimit -1.000000 servo.pid_position.ilimit 0.000000 servo.pid_position.max_desired_rate 0.000000 servo.pid_position.sign -1 servo.current_feedforward 1.000000 servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit nan +servo.default_velocity_limit 5.000000 +servo.default_accel_limit 10.000000 servo.voltage_mode_control 0 servo.fixed_voltage_mode 0 servo.fixed_voltage_control_V 0.000000 @@ -1386,7 +1386,7 @@ servo.flux_brake_min_voltage 53.000000 servo.flux_brake_resistance_ohm 0.025000 servo.max_current_A 5.000000 servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 +servo.max_velocity 10.000000 servo.max_velocity_derate 2.000000 servo.cooldown_cycles 256 servo.velocity_zero_capture_threshold 0.050000 diff --git a/config/moteus/de1/pid_no_load.config b/config/moteus/sa_z.cfg similarity index 97% rename from config/moteus/de1/pid_no_load.config rename to config/moteus/sa_z.cfg index 4ca990e9b..b0654bd1c 100644 --- a/config/moteus/de1/pid_no_load.config +++ b/config/moteus/sa_z.cfg @@ -1,19 +1,19 @@ -uuid.uuid.0 210 -uuid.uuid.1 42 -uuid.uuid.2 55 -uuid.uuid.3 197 -uuid.uuid.4 115 -uuid.uuid.5 183 -uuid.uuid.6 70 -uuid.uuid.7 194 -uuid.uuid.8 179 -uuid.uuid.9 54 -uuid.uuid.10 50 -uuid.uuid.11 137 -uuid.uuid.12 91 -uuid.uuid.13 149 -uuid.uuid.14 200 -uuid.uuid.15 194 +uuid.uuid.0 95 +uuid.uuid.1 37 +uuid.uuid.2 12 +uuid.uuid.3 27 +uuid.uuid.4 4 +uuid.uuid.5 16 +uuid.uuid.6 65 +uuid.uuid.7 193 +uuid.uuid.8 152 +uuid.uuid.9 64 +uuid.uuid.10 17 +uuid.uuid.11 161 +uuid.uuid.12 239 +uuid.uuid.13 203 +uuid.uuid.14 94 +uuid.uuid.15 81 clock.hsitrim 64 aux1.i2c.i2c_hz 400000 aux1.i2c.i2c_mode 1 @@ -38,7 +38,7 @@ aux1.uart.rs422 0 aux1.uart.cui_amt21_address 84 aux1.quadrature.enabled 0 aux1.quadrature.cpr 16384 -aux1.hall.enabled 0 +aux1.hall.enabled 1 aux1.hall.polarity 0 aux1.index.enabled 0 aux1.sine_cosine.enabled 0 @@ -46,12 +46,12 @@ aux1.sine_cosine.common 1700 aux1.i2c_startup_delay_ms 30 aux1.pins.0.mode 0 aux1.pins.0.pull 0 -aux1.pins.1.mode 0 -aux1.pins.1.pull 0 -aux1.pins.2.mode 0 -aux1.pins.2.pull 0 -aux1.pins.3.mode 0 -aux1.pins.3.pull 0 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 6 +aux1.pins.3.pull 1 aux1.pins.4.mode 0 aux1.pins.4.pull 0 aux2.i2c.i2c_hz 400000 @@ -77,29 +77,29 @@ aux2.uart.rs422 0 aux2.uart.cui_amt21_address 84 aux2.quadrature.enabled 0 aux2.quadrature.cpr 16384 -aux2.hall.enabled 1 +aux2.hall.enabled 0 aux2.hall.polarity 0 aux2.index.enabled 0 aux2.sine_cosine.enabled 0 aux2.sine_cosine.common 1700 aux2.i2c_startup_delay_ms 30 -aux2.pins.0.mode 6 +aux2.pins.0.mode 14 aux2.pins.0.pull 1 -aux2.pins.1.mode 6 +aux2.pins.1.mode 14 aux2.pins.1.pull 1 -aux2.pins.2.mode 6 -aux2.pins.2.pull 1 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 aux2.pins.3.mode 0 aux2.pins.3.pull 0 aux2.pins.4.mode 0 aux2.pins.4.pull 0 -motor_position.sources.0.aux_number 2 +motor_position.sources.0.aux_number 1 motor_position.sources.0.type 4 motor_position.sources.0.i2c_device 0 motor_position.sources.0.incremental_index -1 motor_position.sources.0.cpr 48 -motor_position.sources.0.offset -1.000000 -motor_position.sources.0.sign -1 +motor_position.sources.0.offset -3.000000 +motor_position.sources.0.sign 1 motor_position.sources.0.debug_override -1 motor_position.sources.0.reference 0 motor_position.sources.0.pll_filter_hz 100.000000 @@ -224,11 +224,11 @@ motor_position.output.source 0 motor_position.output.offset 0.000000 motor_position.output.sign 1 motor_position.output.reference_source -1 -motor_position.rotor_to_output_ratio 1.000000 +motor_position.rotor_to_output_ratio 0.001587 motor.poles 16 motor.phase_invert 0 -motor.resistance_ohm 3.353775 -motor.v_per_hz 0.571181 +motor.resistance_ohm 4.000340 +motor.v_per_hz 0.575865 motor.offset.0 0.000000 motor.offset.1 0.000000 motor.offset.2 0.000000 @@ -1327,12 +1327,12 @@ drv8323_conf.otw_rep 0 drv8323_conf.pwm_mode 1 drv8323_conf.pwm_1x_asynchronous 0 drv8323_conf.pwm_1x_dir 0 -drv8323_conf.idrivep_hs_ma 150 -drv8323_conf.idriven_hs_ma 300 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 drv8323_conf.cbc 1 drv8323_conf.tdrive_ns 1000 -drv8323_conf.idrivep_ls_ma 150 -drv8323_conf.idriven_ls_ma 300 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 drv8323_conf.tretry 0 drv8323_conf.dead_time_ns 50 drv8323_conf.ocp_mode 0 @@ -1350,7 +1350,7 @@ servo.current_sense_ohm 0.000500 servo.pwm_comp_off 0.027000 servo.pwm_comp_mag 0.005000 servo.pwm_scale 1.000000 -servo.max_voltage 56.000000 +servo.max_voltage 46.000000 servo.max_power_W 450.000000 servo.derate_temperature 50.000000 servo.fault_temperature 75.000000 @@ -1361,19 +1361,19 @@ servo.velocity_threshold 0.000000 servo.position_derate 0.020000 servo.adc_cur_cycles 2 servo.adc_aux_cycles 47 -servo.pid_dq.kp 3.135870 -servo.pid_dq.ki 4214.477539 -servo.pid_position.kp 0.160000 +servo.pid_dq.kp 1.341388 +servo.pid_dq.ki 2513.487549 +servo.pid_position.kp 1500.000000 servo.pid_position.ki 0.000000 -servo.pid_position.kd 0.004500 +servo.pid_position.kd 0.000000 servo.pid_position.iratelimit -1.000000 servo.pid_position.ilimit 0.000000 servo.pid_position.max_desired_rate 0.000000 servo.pid_position.sign -1 servo.current_feedforward 1.000000 servo.bemf_feedforward 1.000000 -servo.default_velocity_limit nan -servo.default_accel_limit nan +servo.default_velocity_limit 0.050000 +servo.default_accel_limit 0.200000 servo.voltage_mode_control 0 servo.fixed_voltage_mode 0 servo.fixed_voltage_control_V 0.000000 @@ -1382,11 +1382,11 @@ servo.max_velocity_slip nan servo.default_timeout_s 0.100000 servo.timeout_max_torque_Nm 5.000000 servo.timeout_mode 12 -servo.flux_brake_min_voltage 53.000000 +servo.flux_brake_min_voltage 43.500000 servo.flux_brake_resistance_ohm 0.025000 -servo.max_current_A 5.000000 +servo.max_current_A 100.000000 servo.derate_current_A -20.000000 -servo.max_velocity 500.000000 +servo.max_velocity 0.100000 servo.max_velocity_derate 2.000000 servo.cooldown_cycles 256 servo.velocity_zero_capture_threshold 0.050000 @@ -1394,6 +1394,6 @@ servo.timing_fault 0 servo.emit_debug 0 servopos.position_min nan servopos.position_max nan -id.id 36 +id.id 49 can.prefix 0 diff --git a/config/teleop.yaml b/config/teleop.yaml index 2158f1ef4..8c05ad09a 100644 --- a/config/teleop.yaml +++ b/config/teleop.yaml @@ -4,54 +4,48 @@ teleop: ra_names: ["joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"] ra_controls: joint_a: - multiplier: 1 + multiplier: -1 slow_mode_multiplier: 0.5 - invert: False + invert: True xbox_index: 0 joint_b: - multiplier: -1 + multiplier: 1 slow_mode_multiplier: 1 - invert: True + invert: False xbox_index: 1 joint_c: multiplier: -1 slow_mode_multiplier: 0.6 - invert: True + invert: False xbox_index: 3 joint_de_pitch: multiplier: 0.5 slow_mode_multiplier: 1 - invert: False - xbox_index_left: 4 - xbox_index_right: 5 + invert: True joint_de_roll: - multiplier: 0.5 + multiplier: -0.5 slow_mode_multiplier: 1 - invert: False - xbox_index_left: 4 - xbox_index_right: 5 + invert: True allen_key: multiplier: 1 slow_mode_multiplier: 1 invert: False - # xbox_index: 7 gripper: multiplier: 1 slow_mode_multiplier: 1 - invert: False - # xbox_index: 7 + invert: True sa_controls: sa_x: multiplier: 1 - slow_mode_multiplier: 0.5 + slow_mode_multiplier: 1.0 # 0.5 xbox_index: 1 sa_y: multiplier: -1 - slow_mode_multiplier: 0.5 + slow_mode_multiplier: 1.0 # 0.5 xbox_index: 0 sa_z: - multiplier: -1 + multiplier: 1 slow_mode_multiplier: 0.5 xbox_index: 4 sampler: @@ -80,20 +74,18 @@ teleop: left_js_y: 1 right_js_x: 2 right_js_y: 3 - left_trigger: 4 - right_trigger: 5 + left_trigger: 6 + right_trigger: 7 a: 0 b: 1 - x: 3 - y: 2 + x: 2 + y: 3 left_bumper: 4 right_bumper: 5 - d_pad_x: 6 - d_pad_y: 7 joystick_mappings: - left_right: 1 - forward_back: 0 + left_right: 0 + forward_back: 1 twist: 2 dampen: 3 pan: 4 diff --git a/launch/esw_base.launch b/launch/esw_base.launch index 8df6aeeeb..e2ccf7d2d 100644 --- a/launch/esw_base.launch +++ b/launch/esw_base.launch @@ -12,43 +12,42 @@ output="screen"> - - - + --> - - - + - + \ No newline at end of file diff --git a/msg/MotorsAdjust.msg b/msg/MotorsAdjust.msg new file mode 100644 index 000000000..93ddff782 --- /dev/null +++ b/msg/MotorsAdjust.msg @@ -0,0 +1,2 @@ +string[] names # names of joints +float32[] values # position should be in radians for the joints \ No newline at end of file diff --git a/msg/Spectral.msg b/msg/Spectral.msg index e03372eb4..4c0376ddb 100644 --- a/msg/Spectral.msg +++ b/msg/Spectral.msg @@ -1,3 +1,3 @@ uint8 site -float64[6] data +float32[6] data bool error \ No newline at end of file diff --git a/msg/SpectralGroup.msg b/msg/SpectralGroup.msg deleted file mode 100644 index 015dc773a..000000000 --- a/msg/SpectralGroup.msg +++ /dev/null @@ -1 +0,0 @@ -Spectral[3] spectrals \ No newline at end of file diff --git a/science-spectral.zip b/science-spectral.zip new file mode 100644 index 000000000..6576025c2 Binary files /dev/null and b/science-spectral.zip differ diff --git a/scripts/plot_bdcmc_debug_messages.py b/scripts/plot_bdcmc_debug_messages.py index 72937d3c2..d8cfaffdd 100644 --- a/scripts/plot_bdcmc_debug_messages.py +++ b/scripts/plot_bdcmc_debug_messages.py @@ -9,6 +9,8 @@ import pyqtgraph as pg from pyqtgraph.Qt import QtCore +from math import pi + if __name__ == "__main__": app = pg.mkQApp() @@ -24,12 +26,12 @@ # curve3 = plot.plot(pen='r') plot.enableAutoRange("xy", True) - plot.setYRange(0, 1 << 14) + plot.setYRange(-pi, pi) xs = np.zeros(40) ys = np.zeros((40, 4)) - with can.interface.Bus(channel="vcan0", interface="socketcan", fd=True) as bus: + with can.interface.Bus(channel="can1", interface="socketcan", fd=True) as bus: def update(): message = bus.recv() diff --git a/src/esw/arm_position_test_bridge/arm_position.cpp b/src/esw/arm_position_test_bridge/arm_position.cpp index 32dc61d23..8229c70b5 100644 --- a/src/esw/arm_position_test_bridge/arm_position.cpp +++ b/src/esw/arm_position_test_bridge/arm_position.cpp @@ -2,135 +2,73 @@ #include "ros/ros.h" #include "std_srvs/SetBool.h" #include -#include -#include #include #include #include void sleep(int ms); -void set_arm_position(ros::Publisher& publisher, std::vector positions, int delay); +void set_arm_position(ros::Publisher& publisher, float position); -std::vector position_data; +float position_data[7] = {0, 0, 0, 0, 0, 0, 0}; -auto arm_position_callback(sensor_msgs::JointState::ConstPtr const& msg) { - ROS_INFO(";)"); +auto arm_position_callback(Position::ConstPtr const& msg) { position_data = msg->position; - ROS_INFO("hey"); } -void reset_pos(ros::Publisher armPublisher, int delay) { - set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}, delay); -} - -void de_roll(float position, ros::Publisher armPublisher, int delay = 5000) { - set_arm_position(armPublisher, {0, 0, 0, 0, 0, position, 0}, delay); - ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); - reset_pos(armPublisher, delay); -} - -void de_pitch(float position, ros::Publisher armPublisher, int delay = 5000) { - set_arm_position(armPublisher, {0, 0, 0, position, 0, 0, 0}, delay); - ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); - reset_pos(armPublisher, delay); -} - -auto main(int argc, char** argv) -> int { - // Delay between operations - int delay = 5000; - position_data.resize(7); - +int main(int argc, char** argv) { ros::init(argc, argv, "arm_position_test_bridge"); ros::NodeHandle nh; ros::Rate rate(10); - ros::Publisher armPublisher = nh.advertise("arm_position_cmd", 1); - ros::Subscriber armSubscriber = nh.subscribe("arm_joint_data", 10, arm_position_callback); - while (ros::ok()) { /* Arm Position Test */ - ROS_INFO("****BEGIN BASIC AUTON ARM POSITION TEST****"); - - - // ROS_INFO("MOVE A"); - - // set_arm_position(armPublisher, {0.4, 0, 0, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - // Test forwards limit switch - //set_arm_position(armPublisher, {1, 0, 0, 0, 0, 0, 0}, delay); - //ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - // Test backwards limit switch - //set_arm_position(armPublisher, {-0.4, 0, 0, 0, 0, 0, 0}, delay); - //ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - - // ROS_INFO("MOVE B"); - // set_arm_position(armPublisher, {0, -0.70, 0, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_B: %f", position_data[1]); - // reset_pos(armPublisher, delay); + ROS_INFO("****BEGIN AUTON ARM POSITION TEST****"); + ros::Publisher armPublisher = nh.advertise("arm_position_cmd", 1); + ros::Subscriber armSubscriber = nh.subscribe("arm_joint_data", 10, arm_position_callback); + + ROS_INFO("MOVE A"); + set_arm_position(armPublisher, {0.4, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_A: %f", position_data[0]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_A: %f", position_data[0]); + sleep(5000); + + ROS_INFO("MOVE B"); + set_arm_position(armPublisher, {0, -0.78, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_B: %f", position_data[1]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_B: %f", position_data[1]); + sleep(5000); ROS_INFO("MOVE C"); - set_arm_position(armPublisher, {0, 0, 2, 0, 0, 0, 0}, delay); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); ROS_INFO("Joint_C: %f", position_data[2]); - reset_pos(armPublisher, delay); - - // set_arm_position(armPublisher, {0, 0, 1.7, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // ROS_INFO("MOVE DE PITCH"); - // float test_de_pitch_positions[4] = {2.35, -2.35, 1.17, -1.17}; - // for(float value : test_de_pitch_positions) { - // de_pitch(value, armPublisher); - // } - - // ROS_INFO("MOVE DE ROLL"); - // float test_de_roll_positions[4] = {6.28, -6.28, 3.14, -3.14}; - // for(float value : test_de_roll_positions){ - // de_roll(value, armPublisher); - // } - ROS_INFO("****END BASIC ARM POSITION TEST****"); - // ROS_INFO("****BEGIN COMPLEX AUTON ARM POSITION TEST****"); - - // ROS_INFO("BOTH DE"); - // for(int i = 0; i < 4; i++){ - // set_arm_position(armPublisher, {0,0,0,0,test_de_pitch_positions[i],test_de_roll_positions[i],0}, delay); - // ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); - // ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); - // reset_pos(armPublisher, delay); - // } - - // // Joint A: [0.0, 1.0] - // // Joint B: [-0.78540, 0.0] - // // Joint C: [-2.094, 1.745] 220 degrees of motion - // // Joint DE-Pitch: [-2.268, 2.268] - // // Joint DE-Roll: [-inf,inf] - // ROS_INFO("A,B,C"); - // //min position - // set_arm_position(armPublisher, {0,-0.78,-2.0,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // // max position - // set_arm_position(armPublisher, {0.9,0.0,1.7,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // set_arm_position(armPublisher, {0.3,-0.32,-1.2,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // ROS_INFO("****END COMPLEX AUTON ARM POSITION TEST****"); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_C: %f", position_data[2]); + sleep(5000); + + ROS_INFO("MOVE DE PITCH"); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); + sleep(5000); + + ROS_INFO("MOVE DE ROLL"); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); + + ROS_INFO("****END ARM POSITION TEST****"); + + nh.spinOnce(); } return 0; @@ -140,15 +78,10 @@ void sleep(int ms) { std::this_thread::sleep_for(std::chrono::milliseconds(ms)); } -void set_arm_position(ros::Publisher& publisher, std::vector positions, int delay) { +void set_arm_position(ros::Publisher& publisher, float positions_arr[7]) { mrover::Position armMsg; // TODO: figure out how to set allen_key and gripper to nan armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - armMsg.positions = std::move(positions); - ROS_INFO("[0]: %f, [1]: %f, [2]: %f", armMsg.positions[0], armMsg.positions[1], armMsg.positions[2]); - - for (int i = 0; i < delay; i += 50) { - sleep(50); - publisher.publish(armMsg); - } + armMsg.positions = positions_arr; + publisher.publish(armMsg); } diff --git a/src/esw/arm_translator_bridge/arm_translator.cpp b/src/esw/arm_translator_bridge/arm_translator.cpp index 058ac7128..56ab622fe 100644 --- a/src/esw/arm_translator_bridge/arm_translator.cpp +++ b/src/esw/arm_translator_bridge/arm_translator.cpp @@ -1,318 +1,208 @@ #include "arm_translator.hpp" -#include "joint_de_translation.hpp" -#include "linear_joint_translation.hpp" - -#include #include +#include +#include + +#include + +namespace Eigen { + + template< + typename Rep1, typename Conversion1, typename MeterExp1, typename KilogramExp1, typename SecondExp1, typename RadianExp1, typename AmpereExp1, typename KelvinExp1, typename ByteExp1, typename TickExp1, + typename Rep2, typename Conversion2, typename MeterExp2, typename KilogramExp2, typename SecondExp2, typename RadianExp2, typename AmpereExp2, typename KelvinExp2, typename ByteExp2, typename TickExp2> + struct ScalarBinaryOpTraits< + mrover::Unit, + mrover::Unit, + internal::scalar_product_op< + mrover::Unit, + mrover::Unit>> { + using U1 = mrover::Unit; + using U2 = mrover::Unit; + using ReturnType = mrover::multiply; + }; + + template<> + struct ScalarBinaryOpTraits< + mrover::Dimensionless, + mrover::Dimensionless, + internal::scalar_product_op> { + using ReturnType = mrover::Dimensionless; + }; + + // template + // struct NumTraits> : NumTraits { + // using U = mrover::Unit; + // using Real = U; + // using NonInteger = U; + // using Nested = U; + // enum { + // IsComplex = 0, + // IsInteger = 0, + // IsSigned = 1, + // RequireInitialization = 1, + // ReadCost = 1, + // AddCost = 3, + // MulCost = 3, + // }; + // }; + +} // namespace Eigen namespace mrover { ArmTranslator::ArmTranslator(ros::NodeHandle& nh) { - assert(mJointDEPitchIndex == mJointDE0Index); - assert(mJointDERollIndex == mJointDE1Index); - assert(mArmHWNames.size() == mRawArmNames.size()); - ROS_INFO("hi"); - for (std::size_t i = 0; i < mRawArmNames.size(); ++i) { - if (i != mJointDEPitchIndex && i != mJointDERollIndex) { - assert(mArmHWNames.at(i) == mRawArmNames.at(i)); - } - { - auto rawName = static_cast(mRawArmNames[i]); - [[maybe_unused]] auto [_, was_inserted] = mAdjustServersByRawArmNames.try_emplace(rawName, nh.advertiseService(std::format("{}_adjust", rawName), &ArmTranslator::adjustServiceCallback, this)); - assert(was_inserted); - } - { - auto hwName = static_cast(mArmHWNames[i]); - [[maybe_unused]] auto [_, was_inserted] = mAdjustClientsByArmHWNames.try_emplace(hwName, nh.serviceClient(std::format("{}_adjust", hwName))); - assert(was_inserted); - } + for (std::string const& hwName: mArmHWNames) { + auto [_, was_inserted] = mAdjustClientsByArmHwNames.try_emplace(hwName, nh.serviceClient(std::format("{}_adjust", hwName))); + assert(was_inserted); } - mJointDEPitchOffset = requireParamAsUnit(nh, "joint_de/pitch_offset"); - mJointDERollOffset = requireParamAsUnit(nh, "joint_de/roll_offset"); - - mMinRadPerSecDE0 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_0/min_velocity"); - mMaxRadPerSecDE0 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_0/max_velocity"); - mMinRadPerSecDE1 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_1/min_velocity"); - mMaxRadPerSecDE1 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_1/max_velocity"); - - mJointDEPitchPosSub = nh.subscribe("joint_de_pitch_raw_position_data", 1, &ArmTranslator::processPitchRawPositionData, this); - mJointDERollPosSub = nh.subscribe("joint_de_roll_raw_position_data", 1, &ArmTranslator::processRollRawPositionData, this); - - mJointALinMult = requireParamAsUnit(nh, "brushless_motors/controllers/joint_a/rad_to_meters_ratio"); - mThrottleSub = nh.subscribe("arm_throttle_cmd", 1, &ArmTranslator::processThrottleCmd, this); mVelocitySub = nh.subscribe("arm_velocity_cmd", 1, &ArmTranslator::processVelocityCmd, this); mPositionSub = nh.subscribe("arm_position_cmd", 1, &ArmTranslator::processPositionCmd, this); - mArmHWJointDataSub = nh.subscribe("arm_hw_joint_data", 1, &ArmTranslator::processArmHWJointData, this); + mJointDataSub = nh.subscribe("arm_hw_joint_data", 1, &ArmTranslator::processJointState, this); mThrottlePub = std::make_unique(nh.advertise("arm_hw_throttle_cmd", 1)); mVelocityPub = std::make_unique(nh.advertise("arm_hw_velocity_cmd", 1)); mPositionPub = std::make_unique(nh.advertise("arm_hw_position_cmd", 1)); mJointDataPub = std::make_unique(nh.advertise("arm_joint_data", 1)); + + mDeOffsetTimer = nh.createTimer(ros::Duration{1}, &ArmTranslator::updateDeOffsets, this); } - // void ArmTranslator::clampValues(float& val1, float& val2, float minValue1, float maxValue1, float minValue2, float maxValue2) { - // val1 = (val1 - (-80)) / (maxValue1 - minValue1) * (); - // val2 if (val1 < minValue1) { - // float const ratio = minValue1 / val1; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (maxValue1 < val1) { - // float const ratio = maxValue1 / val1; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (val2 < minValue2) { - // float const ratio = minValue2 / val2; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (maxValue2 < val2) { - // float const ratio = maxValue2 / val2; - // val1 *= ratio; - // val2 *= ratio; - // } - // } - - auto ArmTranslator::mapValue(float& val, float inputMinValue, float inputMaxValue, float outputMinValue, float outputMaxValue) -> void { - val = (val - inputMinValue) / (inputMaxValue - inputMinValue) * (outputMaxValue - outputMinValue) + outputMinValue; + auto static const PITCH_ROLL_TO_0_1 = (Matrix2{} << -1, -1, -1, 1).finished(); + + auto findJointByName(std::vector const& names, std::string const& name) -> std::optional { + auto it = std::ranges::find(names, name); + return it == names.end() ? std::nullopt : std::make_optional(std::distance(names.begin(), it)); } auto ArmTranslator::processThrottleCmd(Throttle::ConstPtr const& msg) const -> void { - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->throttles.size()) { - ROS_ERROR("Throttle requests for arm is ignored!"); + if (msg->names.size() != msg->throttles.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } Throttle throttle = *msg; - ROS_INFO("pitch throttle: %f roll throttle: %f", msg->throttles.at(mJointDEPitchIndex), msg->throttles.at(mJointDERollIndex)); - - auto [joint_de_0_throttle, joint_de_1_throttle] = transformPitchRollToMotorOutputs( - msg->throttles.at(mJointDEPitchIndex), - msg->throttles.at(mJointDERollIndex)); - ROS_INFO("pre-mapped values: de_0 %f de_1 %f", joint_de_0_throttle, joint_de_1_throttle); + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { - mapValue( - joint_de_0_throttle, - -80.0f, - 80.0f, - -1.0f, - 1.0f); + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - mapValue( - joint_de_1_throttle, - -80.0f, - 80.0f, - -1.0f, - 1.0f); + Vector2 pitchRollThrottles{msg->throttles.at(pitchIndex), msg->throttles.at(rollIndex)}; + Vector2 motorThrottles = PITCH_ROLL_TO_0_1 * pitchRollThrottles; - throttle.names.at(mJointDEPitchIndex) = "joint_de_0"; - throttle.names.at(mJointDERollIndex) = "joint_de_1"; - throttle.throttles.at(mJointDEPitchIndex) = joint_de_0_throttle; - throttle.throttles.at(mJointDERollIndex) = joint_de_1_throttle; - - ROS_INFO("post-mapped values: de_0 %f de_1 %f", joint_de_0_throttle, joint_de_1_throttle); + throttle.names[pitchIndex] = "joint_de_0"; + throttle.names[rollIndex] = "joint_de_1"; + throttle.throttles[pitchIndex] = motorThrottles[0].get(); + throttle.throttles[rollIndex] = motorThrottles[1].get(); + } mThrottlePub->publish(throttle); } - auto ArmTranslator::jointDEIsCalibrated() const -> bool { - return mJointDE0PosOffset.has_value() && mJointDE1PosOffset.has_value(); - } + // constexpr Dimensionless PITCH_ROLL_TO_01_SCALE = 40; + // Matrix2 static const PITCH_ROLL_TO_01_SCALED = PITCH_ROLL_TO_0_1 * PITCH_ROLL_TO_01_SCALE; + // Note (Isabel) PITCH_ROLL_TO_01_SCALE is unnecessary, moteus config will scale for gear ratio - auto ArmTranslator::updatePositionOffsets() -> void { - if (!mCurrentRawJointDEPitch.has_value() || !mCurrentRawJointDERoll.has_value() || !mCurrentRawJointDE0Position.has_value() || !mCurrentRawJointDE1Position.has_value()) { + auto ArmTranslator::processVelocityCmd(Velocity::ConstPtr const& msg) -> void { + if (msg->names.size() != msg->velocities.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } - std::pair expected_motor_outputs = transformPitchRollToMotorOutputs(mCurrentRawJointDEPitch->get(), mCurrentRawJointDERoll->get()); - if (mCurrentRawJointDE0Position.has_value()) { - mJointDE0PosOffset = *mCurrentRawJointDE0Position - Radians{expected_motor_outputs.first}; - } - if (mCurrentRawJointDE1Position.has_value()) { - mJointDE1PosOffset = *mCurrentRawJointDE1Position - Radians{expected_motor_outputs.second}; - } - } + Velocity velocity = *msg; - auto ArmTranslator::processPitchRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void { - mCurrentRawJointDEPitch = Radians{msg->data}; - updatePositionOffsets(); - } + // TODO(quintin): Decrease code duplication + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - auto ArmTranslator::processRollRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void { - mCurrentRawJointDERoll = Radians{msg->data}; - updatePositionOffsets(); - } + Vector2 pitchRollVelocities{msg->velocities.at(pitchIndex), msg->velocities.at(rollIndex)}; + Vector2 motorVelocities = PITCH_ROLL_TO_0_1 * pitchRollVelocities; - auto ArmTranslator::processVelocityCmd(Velocity::ConstPtr const& msg) -> void { - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->velocities.size()) { - ROS_ERROR("Velocity requests for arm is ignored!"); - return; + velocity.names[pitchIndex] = "joint_de_0"; + velocity.names[rollIndex] = "joint_de_1"; + velocity.velocities[pitchIndex] = motorVelocities[0].get(); + velocity.velocities[rollIndex] = motorVelocities[1].get(); } - Velocity velocity = *msg; - - auto [joint_de_0_vel, joint_de_1_vel] = transformPitchRollToMotorOutputs( - msg->velocities.at(mJointDEPitchIndex), - msg->velocities.at(mJointDERollIndex)); - - mapValue( - joint_de_0_vel, - -800.0, - 800.0, - mMinRadPerSecDE1.get(), - mMaxRadPerSecDE1.get()); - - mapValue( - joint_de_1_vel, - -800.0, - 800.0, - mMinRadPerSecDE1.get(), - mMaxRadPerSecDE1.get()); - - velocity.names.at(mJointDEPitchIndex) = "joint_de_0"; - velocity.names.at(mJointDERollIndex) = "joint_de_1"; - velocity.velocities.at(mJointDEPitchIndex) = joint_de_0_vel; - velocity.velocities.at(mJointDERollIndex) = joint_de_1_vel; - - // joint a convert linear velocity (meters/s) to revolution/s - auto joint_a_vel = convertLinVel(msg->velocities.at(mJointAIndex), static_cast(mJointALinMult.get())); - velocity.velocities.at(mJointAIndex) = joint_a_vel; - ROS_INFO("joint a velocity after conversion: %f", joint_a_vel); - mVelocityPub->publish(velocity); } auto ArmTranslator::processPositionCmd(Position::ConstPtr const& msg) -> void { - ROS_INFO("msg: %f", msg->positions[0]); - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->positions.size()) { - ROS_ERROR("Position requests for arm is ignored!"); - return; - } - - if (!jointDEIsCalibrated()) { - ROS_ERROR("Position requests for arm is ignored because jointDEIsNotCalibrated!"); + if (msg->names.size() != msg->positions.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } Position position = *msg; - auto [joint_de_0_raw_pos, joint_de_1_raw_pos] = transformPitchRollToMotorOutputs( - msg->positions.at(mJointDEPitchIndex), - msg->positions.at(mJointDERollIndex)); + // TODO(quintin): Decrease code duplication + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - float joint_de_0_pos = joint_de_0_raw_pos + mJointDE0PosOffset->get(); - float joint_de_1_pos = joint_de_1_raw_pos + mJointDE1PosOffset->get(); + Vector2 pitchRoll{msg->positions.at(pitchIndex), msg->positions.at(rollIndex)}; + Vector2 motorPositions = 40 * PITCH_ROLL_TO_0_1 * pitchRoll; - position.names.at(mJointDEPitchIndex) = "joint_de_0"; - position.names.at(mJointDERollIndex) = "joint_de_1"; - position.positions.at(mJointDEPitchIndex) = joint_de_0_pos; - position.positions.at(mJointDERollIndex) = joint_de_1_pos; + position.names[pitchIndex] = "joint_de_0"; + position.names[rollIndex] = "joint_de_1"; + position.positions[pitchIndex] = motorPositions[0].get(); + position.positions[rollIndex] = motorPositions[1].get(); + } - // joint a convert linear position (meters) to radians - auto joint_a_pos = convertLinPos(msg->positions.at(mJointAIndex), mJointALinMult.get()); - position.positions.at(mJointAIndex) = joint_a_pos; - mPositionPub->publish(position); } - auto ArmTranslator::processArmHWJointData(sensor_msgs::JointState::ConstPtr const& msg) -> void { + auto wrapAngle(float angle) -> float { + constexpr float pi = std::numbers::pi_v; + constexpr float tau = 2 * pi; + return std::fmod(angle + pi, tau) - pi; + } + + auto ArmTranslator::processJointState(sensor_msgs::JointState::ConstPtr const& msg) -> void { if (mArmHWNames != msg->name || mArmHWNames.size() != msg->position.size() || mArmHWNames.size() != msg->velocity.size() || mArmHWNames.size() != msg->effort.size()) { ROS_ERROR("Forwarding joint data for arm is ignored!"); return; } - // Convert joint state of joint a from radians/revolutions to meters - auto jointALinVel = convertLinVel(static_cast(msg->velocity.at(mJointAIndex)), mJointALinMult.get()); - auto jointALinPos = convertLinPos(static_cast(msg->position.at(mJointAIndex)), mJointALinMult.get()); - - sensor_msgs::JointState jointState = *msg; - auto [jointDEPitchVel, jointDERollVel] = transformMotorOutputsToPitchRoll( - static_cast(msg->velocity.at(mJointDE0Index)), - static_cast(msg->velocity.at(mJointDE1Index))); - - [[maybe_unused]] auto [jointDEPitchPos, jointDERollPos] = transformMotorOutputsToPitchRoll( - static_cast(msg->position.at(mJointDE0Index)), - static_cast(msg->position.at(mJointDE1Index))); - - auto [jointDEPitchEff, jointDERollEff] = transformMotorOutputsToPitchRoll( - static_cast(msg->effort.at(mJointDE0Index)), - static_cast(msg->effort.at(mJointDE1Index))); - - mCurrentRawJointDE0Position = Radians{msg->position.at(mJointDE0Index)}; - mCurrentRawJointDE1Position = Radians{msg->position.at(mJointDE1Index)}; - - jointState.name.at(mJointDE0Index) = "joint_de_0"; - jointState.name.at(mJointDE1Index) = "joint_de_1"; - jointState.velocity.at(mJointDE0Index) = jointDEPitchVel; - jointState.velocity.at(mJointDE1Index) = jointDERollVel; - jointState.position.at(mJointDE0Index) = jointDEPitchVel; - jointState.position.at(mJointDE1Index) = jointDERollVel; - jointState.effort.at(mJointDE0Index) = jointDEPitchEff; - jointState.effort.at(mJointDE1Index) = jointDERollEff; - - jointState.velocity.at(mJointAIndex) = jointALinVel; - jointState.position.at(mJointAIndex) = jointALinPos; + std::optional jointDe0Index = findJointByName(msg->name, "joint_de_0"), jointDe1Index = findJointByName(msg->name, "joint_de_1"); + if (jointDe0Index && jointDe1Index) { + auto pitchWrapped = wrapAngle(static_cast(msg->position.at(jointDe0Index.value()))); + auto rollWrapped = wrapAngle(static_cast(msg->position.at(jointDe1Index.value()))); + mJointDePitchRoll = {pitchWrapped, rollWrapped}; + jointState.name[jointDe0Index.value()] = "joint_de_pitch"; + jointState.name[jointDe1Index.value()] = "joint_de_roll"; + jointState.position[jointDe0Index.value()] = pitchWrapped; + jointState.position[jointDe1Index.value()] = rollWrapped; + } mJointDataPub->publish(jointState); } - auto ArmTranslator::adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) -> bool { - - if (req.name == "joint_de_roll") { - mJointDERollAdjust = req.value; - } else if (req.name == "joint_de_pitch") { - mJointDEPitchAdjust = req.value; - } else if (req.name == "joint_a") { - AdjustMotor::Request controllerReq; - AdjustMotor::Response controllerRes = res; - controllerReq.value = convertLinPos(static_cast(req.value), mJointALinMult.get()); - - mAdjustClientsByArmHWNames[req.name].call(controllerReq, controllerRes); - res.success = controllerRes.success; - } else { - AdjustMotor::Request controllerReq = req; - AdjustMotor::Response controllerRes = res; - mAdjustClientsByArmHWNames[req.name].call(controllerReq, controllerRes); - res.success = controllerRes.success; - } + auto ArmTranslator::updateDeOffsets(ros::TimerEvent const&) -> void { + if (!mJointDePitchRoll) return; - if (mJointDEPitchAdjust && mJointDERollAdjust) { - // convert DE_roll and DE_pitch into DE_0 and DE_1 (outgoing message to arm_hw_bridge) - auto [joint_de_0_raw_value, joint_de_1_raw_value] = transformPitchRollToMotorOutputs( - mJointDEPitchAdjust.value(), - mJointDERollAdjust.value()); - mJointDEPitchAdjust = std::nullopt; - mJointDERollAdjust = std::nullopt; - - float joint_de_0_value = joint_de_0_raw_value + mJointDE0PosOffset->get(); - float joint_de_1_value = joint_de_1_raw_value + mJointDE1PosOffset->get(); - - AdjustMotor::Response controllerResDE0; - AdjustMotor::Request controllerReqDE0; - controllerReqDE0.name = "joint_de_0"; - controllerReqDE0.value = joint_de_0_value; - mAdjustClientsByArmHWNames[controllerReqDE0.name].call(controllerResDE0, controllerReqDE0); - - AdjustMotor::Response controllerResDE1; - AdjustMotor::Request controllerReqDE1; - controllerReqDE1.name = "joint_de_1"; - controllerReqDE1.value = joint_de_1_value; - mAdjustClientsByArmHWNames[controllerReqDE1.name].call(controllerReqDE1, controllerResDE1); - - res.success = controllerResDE0.success && controllerResDE1.success; - } else { - // adjust service was for de, but both de joints have not adjusted yet - res.success = false; + Vector2 motorPositions = 40 * PITCH_ROLL_TO_0_1 * mJointDePitchRoll.value(); + { + AdjustMotor adjust; + adjust.request.name = "joint_de_0"; + adjust.request.value = motorPositions[0].get(); + mAdjustClientsByArmHwNames["joint_de_0"].call(adjust); + } + { + AdjustMotor adjust; + adjust.request.name = "joint_de_1"; + adjust.request.value = motorPositions[1].get(); + mAdjustClientsByArmHwNames["joint_de_1"].call(adjust); } - return true; } - -} // namespace mrover \ No newline at end of file +} // namespace mrover diff --git a/src/esw/arm_translator_bridge/arm_translator.hpp b/src/esw/arm_translator_bridge/arm_translator.hpp index 14beae37e..cbab3a91a 100644 --- a/src/esw/arm_translator_bridge/arm_translator.hpp +++ b/src/esw/arm_translator_bridge/arm_translator.hpp @@ -1,12 +1,13 @@ #pragma once -#include "joint_de_translation.hpp" -#include "matrix_helper.hpp" - +#include +#include #include #include +#include #include +#include #include #include @@ -14,23 +15,33 @@ #include #include #include +#include #include #include +#include + #include -#include namespace mrover { + template + using Vector2 = Eigen::Matrix; + + template + using Matrix2 = Eigen::Matrix; + class ArmTranslator { public: ArmTranslator() = default; - explicit ArmTranslator(ros::NodeHandle& nh); + ArmTranslator(ArmTranslator const&) = delete; + ArmTranslator(ArmTranslator&&) = delete; - auto processPitchRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void; + auto operator=(ArmTranslator const&) -> ArmTranslator& = delete; + auto operator=(ArmTranslator&&) -> ArmTranslator& = delete; - auto processRollRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void; + explicit ArmTranslator(ros::NodeHandle& nh); auto processVelocityCmd(Velocity::ConstPtr const& msg) -> void; @@ -38,66 +49,28 @@ namespace mrover { auto processThrottleCmd(Throttle::ConstPtr const& msg) const -> void; - auto processArmHWJointData(sensor_msgs::JointState::ConstPtr const& msg) -> void; + auto processJointState(sensor_msgs::JointState::ConstPtr const& msg) -> void; - auto adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) -> bool; + auto updateDeOffsets(ros::TimerEvent const&) -> void; private: - // static void clampValues(float& val1, float& val2, float minValue1, float maxValue1, float minValue2, float maxValue2); - - static void mapValue(float& val, float inputMinValue, float inputMaxValue, float outputMinValue, float outputMaxValue); - - [[nodiscard]] auto jointDEIsCalibrated() const -> bool; + std::vector const mArmHWNames{"joint_a", "joint_b", "joint_c", "joint_de_0", "joint_de_1", "allen_key", "gripper"}; - auto updatePositionOffsets() -> void; - - const std::vector mRawArmNames{"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - const std::vector mArmHWNames{"joint_a", "joint_b", "joint_c", "joint_de_0", "joint_de_1", "allen_key", "gripper"}; std::unique_ptr mThrottlePub; std::unique_ptr mVelocityPub; std::unique_ptr mPositionPub; std::unique_ptr mJointDataPub; - size_t const mJointDEPitchIndex = std::find(mRawArmNames.begin(), mRawArmNames.end(), "joint_de_pitch") - mRawArmNames.begin(); - size_t const mJointDERollIndex = std::find(mRawArmNames.begin(), mRawArmNames.end(), "joint_de_roll") - mRawArmNames.begin(); - size_t const mJointDE0Index = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_de_0") - mArmHWNames.begin(); - size_t const mJointDE1Index = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_de_1") - mArmHWNames.begin(); - - size_t const mJointAIndex = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_a") - mArmHWNames.begin(); - std::optional mJointDE0PosOffset = Radians{0}; - std::optional mJointDE1PosOffset = Radians{0}; - - Radians mJointDEPitchOffset; - Radians mJointDERollOffset; - - std::optional mCurrentRawJointDEPitch; - std::optional mCurrentRawJointDERoll; - std::optional mCurrentRawJointDE0Position; - std::optional mCurrentRawJointDE1Position; - RadiansPerSecond mMinRadPerSecDE0{}; - RadiansPerSecond mMinRadPerSecDE1{}; - RadiansPerSecond mMaxRadPerSecDE0{}; - RadiansPerSecond mMaxRadPerSecDE1{}; + ros::Timer mDeOffsetTimer; - RadiansPerMeter mJointALinMult{}; // TODO: need to be rev/meter for velocity.... - - ros::Subscriber mJointDEPitchPosSub; - ros::Subscriber mJointDERollPosSub; + std::optional> mJointDePitchRoll; ros::Subscriber mThrottleSub; ros::Subscriber mVelocitySub; ros::Subscriber mPositionSub; - ros::Subscriber mArmHWJointDataSub; - - // TODO:(owen) unique_ptr servers? unique_ptr clients? Both? Neither? The world may never know. (try to learn) - std::unordered_map mAdjustServersByRawArmNames; - // std::unordered_map > mCalibrateServer; - - std::unordered_map mAdjustClientsByArmHWNames; - // std::unique_ptr mCalibrateClient; + ros::Subscriber mJointDataSub; - std::optional mJointDEPitchAdjust; - std::optional mJointDERollAdjust; + std::unordered_map mAdjustClientsByArmHwNames; }; } // namespace mrover diff --git a/src/esw/arm_translator_bridge/joint_de_translation.hpp b/src/esw/arm_translator_bridge/joint_de_translation.hpp deleted file mode 100644 index 3108c321d..000000000 --- a/src/esw/arm_translator_bridge/joint_de_translation.hpp +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once - -#include "matrix_helper.hpp" -#include - -namespace mrover { - - constexpr std::array, 2> CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX = {{{{40, 40}}, - {{40, -40}}}}; - - constexpr std::array, 2> CONVERT_MOTORS_TO_PITCH_ROLL_MATRIX = inverseMatrix(CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX); - - [[maybe_unused]] static auto transformMotorOutputsToPitchRoll(float motor_0, float motor_1) -> std::pair { - - std::array motorsVector = {motor_0, motor_1}; - - // Perform matrix multiplication - auto [pitch, roll] = multiplyMatrixByVector(motorsVector, CONVERT_MOTORS_TO_PITCH_ROLL_MATRIX); - - return std::make_pair(pitch, roll); - } - - // Function to transform coordinates - [[maybe_unused]] static auto transformPitchRollToMotorOutputs(float pitch, float roll) -> std::pair { - // Create the input vector - std::array pitchRollVector = {pitch, roll}; - - // Perform matrix multiplication - auto [m1, m2] = multiplyMatrixByVector(pitchRollVector, CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX); - - return std::make_pair(m1, m2); - } -} // namespace mrover diff --git a/src/esw/arm_translator_bridge/matrix_helper.hpp b/src/esw/arm_translator_bridge/matrix_helper.hpp deleted file mode 100644 index 3b893861e..000000000 --- a/src/esw/arm_translator_bridge/matrix_helper.hpp +++ /dev/null @@ -1,24 +0,0 @@ -#pragma once - -#include - -namespace mrover { - - constexpr std::array, 2> inverseMatrix(std::array, 2> const& matrix) { - float determinant = matrix[0][0] * matrix[1][1] - matrix[0][1] * matrix[1][0]; - float invDet = 1.0f / determinant; - - std::array, 2> result = {{{matrix[1][1] * invDet, -matrix[0][1] * invDet}, - {-matrix[1][0] * invDet, matrix[0][0] * invDet}}}; - - return result; - } - - static std::array multiplyMatrixByVector(std::array const& vector, std::array, 2> const& matrix) { - std::array result = { - matrix[0][0] * vector[0] + matrix[0][1] * vector[1], - matrix[1][0] * vector[0] + matrix[1][1] * vector[1]}; - return result; - } - -} // namespace mrover diff --git a/src/esw/brushless_test_bridge/brushless_test_bridge.cpp b/src/esw/brushless_test_bridge/brushless_test_bridge.cpp index 74eabdcfd..b8b615121 100644 --- a/src/esw/brushless_test_bridge/brushless_test_bridge.cpp +++ b/src/esw/brushless_test_bridge/brushless_test_bridge.cpp @@ -1,3 +1,4 @@ +#include #include #include @@ -5,6 +6,27 @@ #include #include + +// void test_joint_de(ros::NodeHandle& nh) { + +// auto brushlessController_de0 = std::make_unique(nh, "jetson", "joint_de_0"); +// auto brushlessController_de1 = std::make_unique(nh, "jetson", "joint_de_1"); + +// brushlessController_de0->setStop(); +// brushlessController_de1->setStop(); + +// ros::Rate rate{20}; +// while (ros::ok()) { +// brushlessController_de0->setDesiredVelocity(mrover::RadiansPerSecond{60.0}); +// brushlessController_de1->setDesiredVelocity(mrover::RadiansPerSecond{60.0}); + +// ros::spinOnce(); +// rate.sleep(); +// } + + +// } + auto main(int argc, char** argv) -> int { // Initialize the ROS node ros::init(argc, argv, "brushless_test_bridge"); @@ -24,44 +46,64 @@ auto main(int argc, char** argv) -> int { // auto brushlessController_de0 = std::make_unique(nh, "jetson", "joint_de_0"); // auto brushlessController_de1 = std::make_unique(nh, "jetson", "joint_de_1"); - + // fake DE publisher: - auto DEPub = std::make_unique(nh.advertise("arm_velocity_cmd", 1)); - auto SAPub = std::make_unique(nh.advertise("sa_velocity_cmd", 1)); + // auto DEPub = std::make_unique(nh.advertise("arm_velocity_cmd", 1)); + // auto SAPub = std::make_unique(nh.advertise("sa_velocity_cmd", 1)); + auto dePub = nh.advertise("arm_position_cmd", 1); - mrover::Velocity armMsg; - mrover::Velocity saMsg; + mrover::Position armMsg; armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - armMsg.velocities = {0, 0, 0, 20, 20, 0, 0}; + armMsg.positions = {0, 0, 0, 0, 0, 0, 0}; + + std::size_t index = 0; + auto timer = ros::Timer(nh.createTimer(ros::Duration{10}, [&](ros::TimerEvent const&) { + armMsg.positions[3] = std::array{-1, 1, 0, 0, 0, 0, -1}[index]; + armMsg.positions[4] = std::array{0, 0, 0, -3.14, 3.14, 0, 3.14}[index]; + index = (index + 1) % 7; + })); + + ros::Rate rate{20}; + while (ros::ok()) { + dePub.publish(armMsg); + ros::spinOnce(); + rate.sleep(); + } + + // mrover::Velocity armMsg; + // mrover::Velocity saMsg; + // armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; + // armMsg.velocities = {0, 0, 0, 0, -10, 0, 0}; - saMsg.names = {"sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"}; - saMsg.velocities = {0, 0, 0.07,0, 0}; + // saMsg.names = {"sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"}; + // saMsg.velocities = {0, 0, 0.07,0, 0}; // brushlessController_de0->setStop(); // brushlessController_de1->setStop(); - ros::Rate rate{15}; - - int count = 0; - - while(ros::ok()){ - // publish DE velocity: - DEPub->publish(armMsg); - SAPub->publish(saMsg); - count++; + // ros::Rate rate{15}; + // + // int count = 0; + // + // + // while (ros::ok()) { + // // publish DE velocity: + // DEPub->publish(armMsg); + // // SAPub->publish(saMsg); + // count++; + // + // if (count > 100) { + // armMsg.velocities[3] *= -1; + // armMsg.velocities[4] *= -1; + // count = 0; + // } + // + // ros::spinOnce(); + // rate.sleep(); + // } - if(count > 100) { - armMsg.velocities[3] *= -1; - armMsg.velocities[4] *= -1; - count = 0; - } - - ros::spinOnce(); - rate.sleep(); - } return EXIT_SUCCESS; } - diff --git a/src/esw/can_device/can_device.hpp b/src/esw/can_device/can_device.hpp index 9c966deca..464d80bf2 100644 --- a/src/esw/can_device/can_device.hpp +++ b/src/esw/can_device/can_device.hpp @@ -11,7 +11,6 @@ #include -#define CANFD_FDF 0x04 #include namespace mrover { diff --git a/src/esw/drive_bridge/main.cpp b/src/esw/drive_bridge/main.cpp index 7a895dd21..cc30f11b5 100644 --- a/src/esw/drive_bridge/main.cpp +++ b/src/esw/drive_bridge/main.cpp @@ -9,11 +9,9 @@ using namespace mrover; void moveDrive(geometry_msgs::Twist::ConstPtr const& msg); -std::unique_ptr driveManager; -std::vector driveNames{"front_left", "front_right", "middle_left", "middle_right", "back_left", "back_right"}; +ros::Publisher leftVelocityPub, rightVelocityPub; Meters WHEEL_DISTANCE_INNER; -Meters WHEEL_DISTANCE_OUTER; compound_unit> WHEEL_LINEAR_TO_ANGULAR; RadiansPerSecond MAX_MOTOR_SPEED; @@ -24,9 +22,7 @@ auto main(int argc, char** argv) -> int { // Load rover dimensions and other parameters from the ROS parameter server auto roverWidth = requireParamAsUnit(nh, "rover/width"); - auto roverLength = requireParamAsUnit(nh, "rover/length"); WHEEL_DISTANCE_INNER = roverWidth / 2; - WHEEL_DISTANCE_OUTER = sqrt(((roverWidth / 2) * (roverWidth / 2)) + ((roverLength / 2) * (roverLength / 2))); auto ratioMotorToWheel = requireParamAsUnit(nh, "wheel/gear_ratio"); auto wheelRadius = requireParamAsUnit(nh, "wheel/radius"); @@ -38,10 +34,14 @@ auto main(int argc, char** argv) -> int { MAX_MOTOR_SPEED = maxLinearSpeed * WHEEL_LINEAR_TO_ANGULAR; - driveManager = std::make_unique(nh, "drive"); + auto leftGroup = std::make_unique(nh, "drive_left"); + auto rightGroup = std::make_unique(nh, "drive_right"); + + leftVelocityPub = nh.advertise("drive_left_velocity_cmd", 1); + rightVelocityPub = nh.advertise("drive_right_velocity_cmd", 1); // Subscribe to the ROS topic for drive commands - ros::Subscriber moveDriveSubscriber = nh.subscribe("cmd_vel", 1, moveDrive); + auto twistSubscriber = nh.subscribe("cmd_vel", 1, moveDrive); // Enter the ROS event loop ros::spin(); @@ -59,16 +59,17 @@ void moveDrive(geometry_msgs::Twist::ConstPtr const& msg) { RadiansPerSecond left = (forward - delta) * WHEEL_LINEAR_TO_ANGULAR; RadiansPerSecond right = (forward + delta) * WHEEL_LINEAR_TO_ANGULAR; - std::unordered_map driveCommandVelocities{ - {"front_left", left}, - {"front_right", right}, - {"middle_left", left}, - {"middle_right", right}, - {"back_left", left}, - {"back_right", right}, - }; - - for (auto [name, angularVelocity]: driveCommandVelocities) { - driveManager->getController(name).setDesiredVelocity(angularVelocity); + { + Velocity leftVelocity; + leftVelocity.names = {"front_left", "middle_left", "back_left"}; + // TODO(quintin): Invert in firmware + leftVelocity.velocities = {-left.get(), -left.get(), -left.get()}; + leftVelocityPub.publish(leftVelocity); + } + { + Velocity rightVelocity; + rightVelocity.names = {"front_right", "middle_right", "back_right"}; + rightVelocity.velocities = {right.get(), right.get(), right.get()}; + rightVelocityPub.publish(rightVelocity); } } diff --git a/src/esw/fw/bdcmc/.mxproject b/src/esw/fw/bdcmc/.mxproject index 39d7f8d4a..4f2334bec 100644 --- a/src/esw/fw/bdcmc/.mxproject +++ b/src/esw/fw/bdcmc/.mxproject @@ -1,25 +1,25 @@ [PreviousLibFiles] -LibFiles=Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_fdcan.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_def.h;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_bus.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_system.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_utils.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_crs.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ramfunc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dmamux.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_tim.h;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_fdcan.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_def.h;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_bus.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_system.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_utils.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_crs.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ramfunc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dmamux.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_tim.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g431xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g4xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/system_stm32g4xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/core_cm35p.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/cmsis_armclang_ltm.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/core_armv81mml.h;Drivers/CMSIS/Include/cmsis_armclang.h; +LibFiles=Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_fdcan.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_def.h;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_bus.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_system.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_utils.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_crs.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ramfunc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dmamux.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_tim.h;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_fdcan.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_def.h;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_bus.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_system.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_utils.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_crs.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ramfunc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dmamux.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_tim.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\stm32g431xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\stm32g4xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\system_stm32g4xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Drivers\CMSIS\Include\cmsis_armcc.h;Drivers\CMSIS\Include\cmsis_armclang.h;Drivers\CMSIS\Include\cmsis_armclang_ltm.h;Drivers\CMSIS\Include\cmsis_compiler.h;Drivers\CMSIS\Include\cmsis_gcc.h;Drivers\CMSIS\Include\cmsis_iccarm.h;Drivers\CMSIS\Include\cmsis_version.h;Drivers\CMSIS\Include\core_armv81mml.h;Drivers\CMSIS\Include\core_armv8mbl.h;Drivers\CMSIS\Include\core_armv8mml.h;Drivers\CMSIS\Include\core_cm0.h;Drivers\CMSIS\Include\core_cm0plus.h;Drivers\CMSIS\Include\core_cm1.h;Drivers\CMSIS\Include\core_cm23.h;Drivers\CMSIS\Include\core_cm3.h;Drivers\CMSIS\Include\core_cm33.h;Drivers\CMSIS\Include\core_cm35p.h;Drivers\CMSIS\Include\core_cm4.h;Drivers\CMSIS\Include\core_cm7.h;Drivers\CMSIS\Include\core_sc000.h;Drivers\CMSIS\Include\core_sc300.h;Drivers\CMSIS\Include\mpu_armv7.h;Drivers\CMSIS\Include\mpu_armv8.h;Drivers\CMSIS\Include\tz_context.h; [PreviousUsedCubeIDEFiles] -SourceFiles=Core/Src/main.c;Core/Src/stm32g4xx_it.c;Core/Src/stm32g4xx_hal_msp.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Core/Src/system_stm32g4xx.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Core/Src/system_stm32g4xx.c;;; -HeaderPath=Drivers/STM32G4xx_HAL_Driver/Inc;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy;Drivers/CMSIS/Device/ST/STM32G4xx/Include;Drivers/CMSIS/Include;Core/Inc; +SourceFiles=Core\Src\main.c;Core\Src\stm32g4xx_it.c;Core\Src\stm32g4xx_hal_msp.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Core\Src\system_stm32g4xx.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Core\Src\system_stm32g4xx.c;;; +HeaderPath=Drivers\STM32G4xx_HAL_Driver\Inc;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy;Drivers\CMSIS\Device\ST\STM32G4xx\Include;Drivers\CMSIS\Include;Core\Inc; CDefines=USE_HAL_DRIVER;STM32G431xx;USE_HAL_DRIVER;USE_HAL_DRIVER; [PreviousGenFiles] AdvancedFolderStructure=true HeaderFileListSize=3 -HeaderFiles#0=../Core/Inc/stm32g4xx_it.h -HeaderFiles#1=../Core/Inc/stm32g4xx_hal_conf.h -HeaderFiles#2=../Core/Inc/main.h +HeaderFiles#0=..\Core\Inc\stm32g4xx_it.h +HeaderFiles#1=..\Core\Inc\stm32g4xx_hal_conf.h +HeaderFiles#2=..\Core\Inc\main.h HeaderFolderListSize=1 -HeaderPath#0=../Core/Inc +HeaderPath#0=..\Core\Inc HeaderFiles=; SourceFileListSize=3 -SourceFiles#0=../Core/Src/stm32g4xx_it.c -SourceFiles#1=../Core/Src/stm32g4xx_hal_msp.c -SourceFiles#2=../Core/Src/main.c +SourceFiles#0=..\Core\Src\stm32g4xx_it.c +SourceFiles#1=..\Core\Src\stm32g4xx_hal_msp.c +SourceFiles#2=..\Core\Src\main.c SourceFolderListSize=1 -SourcePath#0=../Core/Src +SourcePath#0=..\Core\Src SourceFiles=; diff --git a/src/esw/fw/bdcmc/Core/Inc/controller.hpp b/src/esw/fw/bdcmc/Core/Inc/controller.hpp index f5538f58b..4d8d6902d 100644 --- a/src/esw/fw/bdcmc/Core/Inc/controller.hpp +++ b/src/esw/fw/bdcmc/Core/Inc/controller.hpp @@ -173,15 +173,14 @@ namespace mrover { StateAfterConfig config{.gear_ratio = message.gear_ratio}; if (message.enc_info.quad_present) { - Ratio multiplier = (message.enc_info.quad_is_forward_polarity ? 1 : -1) * message.enc_info.quad_ratio; - if (!m_relative_encoder) m_relative_encoder.emplace(m_encoder_timer, multiplier, m_encoder_elapsed_timer); + if (!m_relative_encoder) m_relative_encoder.emplace(m_encoder_timer, message.enc_info.quad_ratio, m_encoder_elapsed_timer); } if (message.enc_info.abs_present) { - Ratio multiplier = (message.enc_info.abs_is_forward_polarity ? 1 : -1) * message.enc_info.abs_ratio; - if (!m_absolute_encoder) m_absolute_encoder.emplace(AbsoluteEncoderReader::AS5048B_Bus{m_absolute_encoder_i2c}, message.enc_info.abs_offset, multiplier, m_encoder_elapsed_timer); + if (!m_absolute_encoder) m_absolute_encoder.emplace(AbsoluteEncoderReader::AS5048B_Bus{m_absolute_encoder_i2c}, message.enc_info.abs_offset, message.enc_info.abs_ratio, m_encoder_elapsed_timer); } m_motor_driver.change_max_pwm(message.max_pwm); + m_motor_driver.change_inverted(message.is_inverted); config.min_position = message.min_position; config.max_position = message.max_position; @@ -249,10 +248,10 @@ namespace mrover { m_desired_output = mode.pidf.calculate(input, target, cycle_time(m_pidf_timer, CLOCK_FREQ)); m_error = BDCMCErrorInfo::NO_ERROR; - m_fdcan.broadcast(OutBoundMessage{DebugState{ - .f1 = m_velocity.value().get(), - .f2 = message.velocity.get(), - }}); + // m_fdcan.broadcast(OutBoundMessage{DebugState{ + // .f1 = m_velocity.value().get(), + // .f2 = message.velocity.get(), + // }}); } auto process_command(PositionCommand const& message, PositionMode& mode) -> void { @@ -456,12 +455,15 @@ namespace mrover { update(); } + // Max hits before we remove the calibration state + constexpr static std::size_t MAX_MISSED_ABSOLUTE_ENCODER_READS = 32; + auto request_absolute_encoder_data() -> void { // Only read the encoder if we are configured if (m_absolute_encoder) { m_absolute_encoder->request_raw_angle(); // TODO(quintin): No magic numbers - if (m_missed_absolute_encoder_reads++ > 32) { + if (m_missed_absolute_encoder_reads++ > MAX_MISSED_ABSOLUTE_ENCODER_READS) { m_state_after_calib.reset(); } } @@ -488,9 +490,9 @@ namespace mrover { // TODO(quintin): This is pretty stupid m_state_after_calib->offset_position = -position; - m_fdcan.broadcast(OutBoundMessage{DebugState{ - .f1 = position.get(), - }}); + // m_fdcan.broadcast(OutBoundMessage{DebugState{ + // .f1 = position.get(), + // }}); m_uncalib_position.emplace(); // Reset to zero m_velocity = velocity; diff --git a/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp b/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp index c759ff1bf..e01f59fa4 100644 --- a/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp +++ b/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp @@ -7,25 +7,28 @@ namespace mrover { - struct HBridge { + class HBridge { + Pin m_positive_pin{}; + Pin m_negative_pin{}; + TIM_HandleTypeDef* m_timer{}; + std::uint32_t m_channel = TIM_CHANNEL_1; + Percent m_max_pwm{}; + bool m_is_inverted = false; + + public: HBridge() = default; - explicit HBridge(TIM_HandleTypeDef* timer, Pin forward_pin, Pin reverse_pin); + explicit HBridge(TIM_HandleTypeDef* timer, Pin positive_pin, Pin negative_pin); - void write(Percent output) const; + auto write(Percent output) const -> void; - void change_max_pwm(Percent max_pwm); + auto set_direction_pins(Percent duty_cycle) const -> void; - private: - void set_direction_pins(Percent duty_cycle) const; + auto set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const -> void; - void set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const; + auto change_max_pwm(Percent max_pwm) -> void; - Pin m_forward_pins{}; - Pin m_reverse_pins{}; - TIM_HandleTypeDef* m_timer{}; - std::uint32_t m_channel = TIM_CHANNEL_1; - Percent m_max_pwm{}; + auto change_inverted(bool inverted) -> void; }; } // namespace mrover diff --git a/src/esw/fw/bdcmc/Core/Src/hbridge.cpp b/src/esw/fw/bdcmc/Core/Src/hbridge.cpp index 2ca1e595a..3e5f48e2c 100644 --- a/src/esw/fw/bdcmc/Core/Src/hbridge.cpp +++ b/src/esw/fw/bdcmc/Core/Src/hbridge.cpp @@ -5,9 +5,9 @@ namespace mrover { - HBridge::HBridge(TIM_HandleTypeDef* timer, Pin forward_pin, Pin reverse_pin) - : m_forward_pins{forward_pin}, - m_reverse_pins{reverse_pin}, + HBridge::HBridge(TIM_HandleTypeDef* timer, Pin positive_pin, Pin negative_pin) + : m_positive_pin{positive_pin}, + m_negative_pin{negative_pin}, m_timer{timer}, m_max_pwm{0_percent} { @@ -16,18 +16,22 @@ namespace mrover { HAL_TIM_PWM_Start(m_timer, m_channel); } - void HBridge::write(Percent output) const { + auto HBridge::write(Percent output) const -> void { // Set direction pins/duty cycle set_direction_pins(output); set_duty_cycle(output, m_max_pwm); } - void HBridge::set_direction_pins(Percent duty_cycle) const { - m_forward_pins.write(duty_cycle < 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET); - m_reverse_pins.write(duty_cycle > 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET); + auto HBridge::set_direction_pins(Percent duty_cycle) const -> void { + // TODO(quintin): Guthrie says only one of these pins is actually used? + GPIO_PinState positive_state = duty_cycle > 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET; + GPIO_PinState negative_state = duty_cycle < 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET; + if (m_is_inverted) std::swap(positive_state, negative_state); + m_positive_pin.write(positive_state); + m_negative_pin.write(negative_state); } - void HBridge::set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const { + auto HBridge::set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const -> void { // Clamp absolute value of the duty cycle to the supported range duty_cycle = std::clamp(abs(duty_cycle), 0_percent, max_duty_cycle); @@ -39,8 +43,12 @@ namespace mrover { // TODO(quintin) we should error if the registers are null pointers } - void HBridge::change_max_pwm(Percent max_pwm) { + auto HBridge::change_max_pwm(Percent max_pwm) -> void { m_max_pwm = max_pwm; } + auto HBridge::change_inverted(bool inverted) -> void { + m_is_inverted = inverted; + } + } // namespace mrover \ No newline at end of file diff --git a/src/esw/fw/bdcmc/Core/Src/main.c b/src/esw/fw/bdcmc/Core/Src/main.c index 2b17a80ae..f0f572550 100644 --- a/src/esw/fw/bdcmc/Core/Src/main.c +++ b/src/esw/fw/bdcmc/Core/Src/main.c @@ -89,7 +89,6 @@ void HAL_PostInit(); */ int main(void) { - /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ @@ -245,7 +244,7 @@ static void MX_FDCAN1_Init(void) hfdcan1.Init.DataTimeSeg1 = 14; hfdcan1.Init.DataTimeSeg2 = 13; hfdcan1.Init.StdFiltersNbr = 0; - hfdcan1.Init.ExtFiltersNbr = 0; + hfdcan1.Init.ExtFiltersNbr = 1; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) { diff --git a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c index 1ebcf1654..eb37487cb 100644 --- a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c +++ b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c @@ -20,6 +20,7 @@ /* Includes ------------------------------------------------------------------*/ #include "main.h" + /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ @@ -67,7 +68,6 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); */ void HAL_MspInit(void) { - /* USER CODE BEGIN MspInit 0 */ /* USER CODE END MspInit 0 */ diff --git a/src/esw/fw/bdcmc/bdcmc.ioc b/src/esw/fw/bdcmc/bdcmc.ioc index cc4874ff7..df4ab75e2 100644 --- a/src/esw/fw/bdcmc/bdcmc.ioc +++ b/src/esw/fw/bdcmc/bdcmc.ioc @@ -47,8 +47,9 @@ FDCAN1.DataPrescaler=1 FDCAN1.DataSyncJumpWidth=13 FDCAN1.DataTimeSeg1=14 FDCAN1.DataTimeSeg2=13 +FDCAN1.ExtFiltersNbr=1 FDCAN1.FrameFormat=FDCAN_FRAME_FD_NO_BRS -FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,NominalSyncJumpWidth,DataPrescaler,DataSyncJumpWidth,DataTimeSeg1,DataTimeSeg2,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,Mode,AutoRetransmission +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,NominalSyncJumpWidth,DataPrescaler,DataSyncJumpWidth,DataTimeSeg1,DataTimeSeg2,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,Mode,AutoRetransmission,ExtFiltersNbr FDCAN1.Mode=FDCAN_MODE_NORMAL FDCAN1.NominalPrescaler=1 FDCAN1.NominalSyncJumpWidth=19 @@ -114,8 +115,8 @@ Mcu.PinsNb=32 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32G431CBUx -MxCube.Version=6.11.0 -MxDb.Version=DB.6.0.110 +MxCube.Version=6.10.0 +MxDb.Version=DB.6.0.100 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.DMA1_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true NVIC.DMA1_Channel2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true diff --git a/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp b/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp index 151f77556..39e9ccd85 100644 --- a/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp +++ b/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp @@ -9,6 +9,8 @@ #include #include +// TMP6431DECR + namespace mrover { class DiagTempSensor { diff --git a/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp b/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp index 8c7bcd597..f3f2a4c95 100644 --- a/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp +++ b/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp @@ -5,6 +5,8 @@ #include +// TMP6431DECR + namespace mrover { constexpr static float DIAG_TEMP_COEFFICIENT = 0.0064f; @@ -23,6 +25,7 @@ namespace mrover { void DiagTempSensor::update_temp() { uint16_t adc_val = m_adc_sensor->get_raw_channel_value(m_channel); float measured_volts = (adc_val * 3.3f) / 4096.0f; + m_temp = (THRM_A4 * powf(measured_volts,4)) + (THRM_A3 * powf(measured_volts,3)) + (THRM_A2 * powf(measured_volts,2)) + (THRM_A1 * measured_volts) + THRM_A0; } diff --git a/src/esw/fw/pdlb/Core/Src/main.c b/src/esw/fw/pdlb/Core/Src/main.c index 10d641360..98a6fe28c 100644 --- a/src/esw/fw/pdlb/Core/Src/main.c +++ b/src/esw/fw/pdlb/Core/Src/main.c @@ -205,6 +205,7 @@ int main(void) /* Start scheduler */ osKernelStart(); + /* We should never get here as control is now taken by the scheduler */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ @@ -317,7 +318,7 @@ static void MX_ADC1_Init(void) */ sConfig.Channel = ADC_CHANNEL_1; sConfig.Rank = ADC_REGULAR_RANK_1; - sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SamplingTime = ADC_SAMPLETIME_12CYCLES_5; sConfig.SingleDiff = ADC_SINGLE_ENDED; sConfig.OffsetNumber = ADC_OFFSET_NONE; sConfig.Offset = 0; @@ -457,7 +458,7 @@ static void MX_ADC2_Init(void) */ sConfig.Channel = ADC_CHANNEL_10; sConfig.Rank = ADC_REGULAR_RANK_1; - sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SamplingTime = ADC_SAMPLETIME_640CYCLES_5; sConfig.SingleDiff = ADC_SINGLE_ENDED; sConfig.OffsetNumber = ADC_OFFSET_NONE; sConfig.Offset = 0; @@ -511,7 +512,7 @@ static void MX_FDCAN1_Init(void) hfdcan1.Init.DataTimeSeg1 = 14; hfdcan1.Init.DataTimeSeg2 = 13; hfdcan1.Init.StdFiltersNbr = 0; - hfdcan1.Init.ExtFiltersNbr = 0; + hfdcan1.Init.ExtFiltersNbr = 1; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) { @@ -624,7 +625,7 @@ void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs) void SendCurrentTemperature(void* argument) { for(;;) { - uint32_t tick = osKernelGetTickCount() + osKernelGetTickFreq(); // 1 Hz + uint32_t tick = osKernelGetTickCount() + (osKernelGetTickFreq() / 10.0); // 10 Hz update_and_send_current_temp(); osDelayUntil(tick); diff --git a/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c b/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c index e8a63291c..4685060eb 100644 --- a/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c +++ b/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c @@ -20,6 +20,7 @@ /* Includes ------------------------------------------------------------------*/ #include "main.h" + /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ @@ -152,8 +153,8 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc1.Init.MemInc = DMA_MINC_ENABLE; - hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; hdma_adc1.Init.Mode = DMA_NORMAL; hdma_adc1.Init.Priority = DMA_PRIORITY_LOW; if (HAL_DMA_Init(&hdma_adc1) != HAL_OK) @@ -211,8 +212,8 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc2.Init.MemInc = DMA_MINC_ENABLE; - hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; hdma_adc2.Init.Mode = DMA_NORMAL; hdma_adc2.Init.Priority = DMA_PRIORITY_LOW; if (HAL_DMA_Init(&hdma_adc2) != HAL_OK) diff --git a/src/esw/fw/pdlb/pdlb.ioc b/src/esw/fw/pdlb/pdlb.ioc index 7d0bf72af..90d1e4a67 100644 --- a/src/esw/fw/pdlb/pdlb.ioc +++ b/src/esw/fw/pdlb/pdlb.ioc @@ -33,16 +33,16 @@ ADC1.Rank-6\#ChannelRegularConversion=7 ADC1.Rank-7\#ChannelRegularConversion=8 ADC1.Rank-8\#ChannelRegularConversion=9 ADC1.Rank-9\#ChannelRegularConversion=10 -ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-7\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-8\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-9\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 +ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-7\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-8\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-9\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 ADC1.master=1 ADC2.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_10 ADC2.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_15 @@ -54,18 +54,18 @@ ADC2.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE ADC2.OffsetNumber-1\#ChannelRegularConversion=ADC_OFFSET_NONE ADC2.Rank-0\#ChannelRegularConversion=1 ADC2.Rank-1\#ChannelRegularConversion=2 -ADC2.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 +ADC2.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_640CYCLES_5 +ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_640CYCLES_5 CAD.formats= CAD.pinconfig= CAD.provider= Dma.ADC1.0.Direction=DMA_PERIPH_TO_MEMORY Dma.ADC1.0.EventEnable=DISABLE Dma.ADC1.0.Instance=DMA1_Channel1 -Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_HALFWORD +Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_WORD Dma.ADC1.0.MemInc=DMA_MINC_ENABLE Dma.ADC1.0.Mode=DMA_NORMAL -Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD +Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_WORD Dma.ADC1.0.PeriphInc=DMA_PINC_DISABLE Dma.ADC1.0.Polarity=HAL_DMAMUX_REQ_GEN_RISING Dma.ADC1.0.Priority=DMA_PRIORITY_LOW @@ -79,10 +79,10 @@ Dma.ADC1.0.SyncSignalID=NONE Dma.ADC2.1.Direction=DMA_PERIPH_TO_MEMORY Dma.ADC2.1.EventEnable=DISABLE Dma.ADC2.1.Instance=DMA1_Channel2 -Dma.ADC2.1.MemDataAlignment=DMA_MDATAALIGN_HALFWORD +Dma.ADC2.1.MemDataAlignment=DMA_MDATAALIGN_WORD Dma.ADC2.1.MemInc=DMA_MINC_ENABLE Dma.ADC2.1.Mode=DMA_NORMAL -Dma.ADC2.1.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD +Dma.ADC2.1.PeriphDataAlignment=DMA_PDATAALIGN_WORD Dma.ADC2.1.PeriphInc=DMA_PINC_DISABLE Dma.ADC2.1.Polarity=HAL_DMAMUX_REQ_GEN_RISING Dma.ADC2.1.Priority=DMA_PRIORITY_LOW @@ -104,8 +104,9 @@ FDCAN1.DataPrescaler=5 FDCAN1.DataSyncJumpWidth=13 FDCAN1.DataTimeSeg1=14 FDCAN1.DataTimeSeg2=13 +FDCAN1.ExtFiltersNbr=1 FDCAN1.FrameFormat=FDCAN_FRAME_FD_NO_BRS -FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,DataSyncJumpWidth,NominalSyncJumpWidth,NominalTimeSeg1,NominalTimeSeg2,NominalPrescaler,DataTimeSeg1,DataTimeSeg2,TransmitPause,AutoRetransmission,DataPrescaler +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,DataSyncJumpWidth,NominalSyncJumpWidth,NominalTimeSeg1,NominalTimeSeg2,NominalPrescaler,DataTimeSeg1,DataTimeSeg2,TransmitPause,AutoRetransmission,DataPrescaler,ExtFiltersNbr FDCAN1.NominalPrescaler=1 FDCAN1.NominalSyncJumpWidth=19 FDCAN1.NominalTimeSeg1=120 @@ -157,8 +158,8 @@ Mcu.PinsNb=24 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32G431CBUx -MxCube.Version=6.8.1 -MxDb.Version=DB.6.0.81 +MxCube.Version=6.10.0 +MxDb.Version=DB.6.0.100 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false NVIC.DMA1_Channel1_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true NVIC.DMA1_Channel2_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true @@ -276,7 +277,7 @@ ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x200 ProjectManager.KeepUserCode=true -ProjectManager.LastFirmware=true +ProjectManager.LastFirmware=false ProjectManager.LibraryCopy=1 ProjectManager.MainLocation=Core/Src ProjectManager.NoMain=false diff --git a/src/esw/fw/science/Core/Src/heater.cpp b/src/esw/fw/science/Core/Src/heater.cpp index 80c5c5b97..6cfeb20e8 100644 --- a/src/esw/fw/science/Core/Src/heater.cpp +++ b/src/esw/fw/science/Core/Src/heater.cpp @@ -16,7 +16,7 @@ namespace mrover { : m_diag_temp_sensor(std::move(diag_temp_sensor)), m_heater_pin(std::move(heater_pin)), m_state(false), - m_auto_shutoff_enabled(true), + m_auto_shutoff_enabled(true), // TODO - may want to make true if thermistors work m_last_time_received_message(0) {} diff --git a/src/esw/fw/science/Core/Src/science.cpp b/src/esw/fw/science/Core/Src/science.cpp index bd7caf132..80c9db563 100644 --- a/src/esw/fw/science/Core/Src/science.cpp +++ b/src/esw/fw/science/Core/Src/science.cpp @@ -130,8 +130,26 @@ void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* hfdcan, uint32_t RxFifo0ITs) } } +//void HAL_I2C_MasterTXCpltCallback(I2C_HandleTypeDef *hi2c) { +// HAL_I2C_Master_Receive_IT(hi2c, (mrover::Spectral::SPECTRAL_7b_ADDRESS << 1 | 1), (uint8_t*)spectral_status_buffer, sizeof(spectral_status_buffer)); +//} +// +//void HAL_I2C_MasterRXCpltCallback(I2C_HandleTypeDef *hi2c) { +// // If we want to use this for anything else than checking spectral status reg, +// // then this function needs additional logic +// +// if ((spectral_status_buffer[0] & mrover::Spectral::I2C_AS72XX_SLAVE_TX_VALID) == 0) { +// osSemaphoreRelease(spectral_write_status); +// } +// +// if ((spectral_status_buffer[0] & mrover::Spectral::I2C_AS72XX_SLAVE_RX_VALID) == 0) { +// osSemaphoreRelease(spectral_read_status); +// } +// +//} + void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) { // Something is most likely wrong with the I2C bus // if we get to this point mrover::science.reboot_i2c(); -} \ No newline at end of file +} diff --git a/src/esw/fw/science/Core/Src/spectral.cpp b/src/esw/fw/science/Core/Src/spectral.cpp index 11b10fc07..410ee8f20 100644 --- a/src/esw/fw/science/Core/Src/spectral.cpp +++ b/src/esw/fw/science/Core/Src/spectral.cpp @@ -41,11 +41,13 @@ namespace mrover { else { m_error = true; m_initialized = false; +// return; } osDelay(5); // Non blocking delay } + //throw mrover::I2CRuntimeError("SPECTRAL"); m_error = true; m_initialized = false; } @@ -63,6 +65,8 @@ namespace mrover { // DATA_RDY is 0 and RSVD is 0 virtual_write(CONTROL_SETUP_REG, control_data); osDelay(50); +// virtual_write(CONTROL_SETUP_REG, control_data); +// osDelay(50); // Integration time = 2.8ms & 0xFF uint8_t int_time_multiplier = 0xFF; //0xFF; @@ -111,12 +115,19 @@ namespace mrover { void Spectral::virtual_write(uint8_t virtual_reg, uint8_t data) { poll_status_reg(I2C_OP::WRITE); - uint8_t buf[2] = {I2C_AS72XX_WRITE_REG, (virtual_reg | 0x80)}; - m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf); - + uint8_t buf[2]; + buf[0] = I2C_AS72XX_WRITE_REG; + buf[1] = (virtual_reg | 0x80); +// m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf[0]); + // How to send multiple bytes? + HAL_I2C_Master_Transmit(&hi2c1, SPECTRAL_7b_ADDRESS << 1, buf, sizeof(buf), 100); + poll_status_reg(I2C_OP::WRITE); buf[1] = data; - m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf); +// m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf[0]); + + HAL_I2C_Master_Transmit(&hi2c1, SPECTRAL_7b_ADDRESS << 1, buf, sizeof(buf), 100); + } uint8_t Spectral::virtual_read(uint8_t virtual_reg) { @@ -144,9 +155,14 @@ namespace mrover { if (m_error) { return 0; } - uint8_t buf[2] = {I2C_AS72XX_WRITE_REG, virtual_reg}; + uint8_t buf[2]; + buf[0] = I2C_AS72XX_WRITE_REG; + buf[1] = virtual_reg; + HAL_I2C_Master_Transmit(&hi2c1, SPECTRAL_7b_ADDRESS << 1, buf, sizeof(buf), 100); + // UNABLE TO USE this format because TSend is 1 byte, need to double up + // TODO resolve this somehow... +// m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf[0]); - m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, buf); poll_status_reg(I2C_OP::READ); @@ -155,6 +171,8 @@ namespace mrover { } auto result = m_i2c_bus->blocking_transact(SPECTRAL_7b_ADDRESS, I2C_AS72XX_READ_REG); +// m_i2c_bus->blocking_transmit(SPECTRAL_7b_ADDRESS, I2C_AS72XX_READ_REG); +// auto result = m_i2c_bus->blocking_receive(SPECTRAL_7b_ADDRESS); if(!result.has_value()){ m_error = true; return 0; diff --git a/src/esw/led/main.cpp b/src/esw/led/main.cpp index 55a9a2a0a..8e1220683 100644 --- a/src/esw/led/main.cpp +++ b/src/esw/led/main.cpp @@ -13,7 +13,7 @@ enum class LEDMode { Blue = 4 }; -static constexpr std::string DONE_STATE = "DoneState"; +static constexpr std::string_view DONE_STATE = "DoneState"; ros::Publisher led_publisher; diff --git a/src/esw/mast_gimbal_bridge/main.cpp b/src/esw/mast_gimbal_bridge/main.cpp index 3a7d7bad2..8dcc84b01 100644 --- a/src/esw/mast_gimbal_bridge/main.cpp +++ b/src/esw/mast_gimbal_bridge/main.cpp @@ -8,7 +8,7 @@ auto main(int argc, char** argv) -> int { ros::NodeHandle nh; // Load motor controllers configuration from the ROS parameter server - [[maybe_unused]] auto mastGimbalManager = std::make_unique(nh, "mast_gimbal"); + mrover::MotorsGroup group{nh, "mast_gimbal"}; // Enter the ROS event loop ros::spin(); diff --git a/src/esw/motor_library/brushed.cpp b/src/esw/motor_library/brushed.cpp index 9f7448fbb..46d84f085 100644 --- a/src/esw/motor_library/brushed.cpp +++ b/src/esw/motor_library/brushed.cpp @@ -2,19 +2,14 @@ namespace mrover { - BrushedController::BrushedController(ros::NodeHandle const& nh, std::string name, std::string controllerName) - : Controller{nh, std::move(name), std::move(controllerName)} { + BrushedController::BrushedController(ros::NodeHandle const& nh, std::string masterName, std::string controllerName) + : ControllerBase{nh, std::move(masterName), std::move(controllerName)} { XmlRpc::XmlRpcValue brushedMotorData; assert(mNh.hasParam(std::format("brushed_motors/controllers/{}", mControllerName))); mNh.getParam(std::format("brushed_motors/controllers/{}", mControllerName), brushedMotorData); assert(brushedMotorData.getType() == XmlRpc::XmlRpcValue::TypeStruct); - mVelocityMultiplier = Dimensionless{xmlRpcValueToTypeOrDefault(brushedMotorData, "velocity_multiplier", 1.0)}; - if (mVelocityMultiplier.get() == 0) { - throw std::runtime_error("Velocity multiplier can't be 0!"); - } - mConfigCommand.gear_ratio = xmlRpcValueToTypeOrDefault(brushedMotorData, "gear_ratio"); for (std::size_t i = 0; i < 4; ++i) { @@ -26,12 +21,12 @@ namespace mrover { mConfigCommand.limit_switch_info.limit_readj_pos.at(i) = Radians{static_cast(brushedMotorData[std::format("limit_{}_readjust_position", i)])}; } + mConfigCommand.is_inverted = xmlRpcValueToTypeOrDefault(brushedMotorData, "is_inverted", false); + mConfigCommand.enc_info.quad_present = xmlRpcValueToTypeOrDefault(brushedMotorData, "quad_present", false); - mConfigCommand.enc_info.quad_is_forward_polarity = xmlRpcValueToTypeOrDefault(brushedMotorData, "quad_is_fwd_polarity", false); mConfigCommand.enc_info.quad_ratio = xmlRpcValueToTypeOrDefault(brushedMotorData, "quad_ratio", 1.0); mConfigCommand.enc_info.abs_present = xmlRpcValueToTypeOrDefault(brushedMotorData, "abs_present", false); - mConfigCommand.enc_info.abs_is_forward_polarity = xmlRpcValueToTypeOrDefault(brushedMotorData, "abs_is_fwd_polarity", false); mConfigCommand.enc_info.abs_ratio = xmlRpcValueToTypeOrDefault(brushedMotorData, "abs_ratio", 1.0); mConfigCommand.enc_info.abs_offset = Radians{xmlRpcValueToTypeOrDefault(brushedMotorData, "abs_offset", 0.0)}; @@ -62,7 +57,7 @@ namespace mrover { mVelocityGains.ff = xmlRpcValueToTypeOrDefault(brushedMotorData, "velocity_ff", 0.0); for (int i = 0; i < 4; ++i) { - mhasLimit |= xmlRpcValueToTypeOrDefault(brushedMotorData, std::format("limit_{}_enabled", i), false); + mHasLimit |= xmlRpcValueToTypeOrDefault(brushedMotorData, std::format("limit_{}_enabled", i), false); } mCalibrationThrottle = Percent{xmlRpcValueToTypeOrDefault(brushedMotorData, "calibration_throttle", 0.0)}; mErrorState = "Unknown"; @@ -104,8 +99,6 @@ namespace mrover { assert(velocity >= mConfigCommand.min_velocity && velocity <= mConfigCommand.max_velocity); - velocity = velocity * mVelocityMultiplier; - mDevice.publish_message(InBoundMessage{VelocityCommand{ .velocity = velocity, .p = static_cast(mVelocityGains.p), @@ -134,7 +127,7 @@ namespace mrover { auto BrushedController::processMessage(ControllerDataState const& state) -> void { mCurrentPosition = state.position; - mCurrentVelocity = state.velocity / mVelocityMultiplier; + mCurrentVelocity = state.velocity; ConfigCalibErrorInfo configCalibErrInfo = state.config_calib_error_data; mIsConfigured = configCalibErrInfo.configured; mIsCalibrated = configCalibErrInfo.calibrated; @@ -152,7 +145,7 @@ namespace mrover { auto BrushedController::processCANMessage(CAN::ConstPtr const& msg) -> void { assert(msg->source == mControllerName); - assert(msg->destination == mName); + assert(msg->destination == mMasterName); OutBoundMessage const& message = *reinterpret_cast(msg->data.data()); @@ -184,14 +177,14 @@ namespace mrover { } auto BrushedController::calibrateServiceCallback([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res) -> bool { - if (!mhasLimit) { + if (!mHasLimit) { res.success = false; - res.message = mControllerName + " does not have limit switches, cannot calibrate"; + res.message = std::format("{} does not have limit switches, cannot calibrate", mControllerName); return true; } if (mIsCalibrated) { res.success = false; - res.message = mControllerName + " already calibrated"; + res.message = std::format("{} already calibrated", mControllerName); return true; } // sends throttle command until a limit switch is hit diff --git a/src/esw/motor_library/brushed.hpp b/src/esw/motor_library/brushed.hpp index 9b1339ed3..a7dd59629 100644 --- a/src/esw/motor_library/brushed.hpp +++ b/src/esw/motor_library/brushed.hpp @@ -15,32 +15,35 @@ namespace mrover { double p{}, i{}, d{}, ff{}; }; - class BrushedController : public Controller { + // For now only revolute joints are supported => hardcode to Radians + class BrushedController final : public ControllerBase { public: - void setDesiredThrottle(Percent throttle) override; // from -1.0 to 1.0 - void setDesiredVelocity(RadiansPerSecond velocity) override; - void setDesiredPosition(Radians position) override; - void adjust(Radians position) override; + BrushedController(ros::NodeHandle const& nh, std::string masterName, std::string controllerName); - void processCANMessage(CAN::ConstPtr const& msg) override; + auto setDesiredThrottle(Percent throttle) -> void; // from -1.0 to 1.0 - void processMessage(ControllerDataState const& state); + auto setDesiredPosition(Radians position) -> void; - void processMessage(DebugState const&) {} + auto setDesiredVelocity(RadiansPerSecond velocity) -> void; - void sendConfiguration(); + auto adjust(Radians position) -> void; - double getEffort() override; + auto processCANMessage(CAN::ConstPtr const& msg) -> void; - BrushedController(ros::NodeHandle const& nh, std::string name, std::string controllerName); - ~BrushedController() override = default; + auto processMessage(ControllerDataState const& state) -> void; - bool calibrateServiceCallback(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res); + auto processMessage(DebugState const&) -> void {} + + auto sendConfiguration() -> void; + + auto getEffort() -> double; + + auto calibrateServiceCallback(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res) -> bool; private: - static std::string errorToString(BDCMCErrorInfo errorCode); + static auto errorToString(BDCMCErrorInfo errorCode) -> std::string; - bool mIsConfigured = false; + bool mIsConfigured{false}; ConfigCommand mConfigCommand; Gains mPositionGains; diff --git a/src/esw/motor_library/brushless.cpp b/src/esw/motor_library/brushless.cpp deleted file mode 100644 index 070e250c7..000000000 --- a/src/esw/motor_library/brushless.cpp +++ /dev/null @@ -1,302 +0,0 @@ -#include "brushless.hpp" -#include "moteus/moteus_protocol.h" -#include -#include - -namespace mrover { - - BrushlessController::BrushlessController(ros::NodeHandle const& nh, std::string name, std::string controllerName) - : Controller{nh, std::move(name), std::move(controllerName)} { - - XmlRpc::XmlRpcValue brushlessMotorData; - assert(mNh.hasParam(std::format("brushless_motors/controllers/{}", mControllerName))); - mNh.getParam(std::format("brushless_motors/controllers/{}", mControllerName), brushlessMotorData); - assert(brushlessMotorData.getType() == XmlRpc::XmlRpcValue::TypeStruct); - - mVelocityMultiplier = Dimensionless{xmlRpcValueToTypeOrDefault(brushlessMotorData, "velocity_multiplier", 1.0)}; - if (mVelocityMultiplier.get() == 0) { - throw std::runtime_error("Velocity multiplier can't be 0!"); - } - - mMinVelocity = RadiansPerSecond{xmlRpcValueToTypeOrDefault(brushlessMotorData, "min_velocity", -0.01)}; - mMaxVelocity = RadiansPerSecond{xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_velocity", 0.01)}; - - mMinPosition = Radians{xmlRpcValueToTypeOrDefault(brushlessMotorData, "min_position", -1.0)}; - mMaxPosition = Radians{xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_position", 1.0)}; - - mMaxTorque = xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_torque", 0.3); - mWatchdogTimeout = xmlRpcValueToTypeOrDefault(brushlessMotorData, "watchdog_timeout", 0.1); - - limitSwitch0Present = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_present", false); - limitSwitch1Present = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_present", false); - limitSwitch0Enabled = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_enabled", true); - limitSwitch1Enabled = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_enabled", true); - limitSwitch0LimitsFwd = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_limits_fwd", false); - limitSwitch1LimitsFwd = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_limits_fwd", false); - limitSwitch0ActiveHigh = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_is_active_high", true); - limitSwitch1ActiveHigh = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_is_active_high", true); - limitSwitch0UsedForReadjustment = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_used_for_readjustment", false); - limitSwitch1UsedForReadjustment = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_used_for_readjustment", false); - limitSwitch0ReadjustPosition = Radians{xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_readjust_position", 0.0)}; - limitSwitch1ReadjustPosition = Radians{xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_readjust_position", 0.0)}; - - } - - auto BrushlessController::setDesiredThrottle(Percent throttle) -> void { - setDesiredVelocity(mapThrottleToVelocity(throttle)); - } - - auto BrushlessController::setDesiredPosition(Radians position) -> void { - // only check for limit switches if at least one limit switch exists and is enabled - if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { - sendQuery(); - - MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); - if ((mCurrentPosition < position && limitSwitchInfo.isFwdPressed) || (mCurrentPosition > position && limitSwitchInfo.isBwdPressed)) { - setBrake(); - return; - } - } - - Revolutions position_revs = std::clamp(position, mMinPosition, mMaxPosition); - moteus::PositionMode::Command command{ - .position = position_revs.get(), - .velocity = 0.0, - .maximum_torque = mMaxTorque, - .watchdog_timeout = mWatchdogTimeout, - }; - moteus::CanFdFrame positionFrame = mController.MakePosition(command); - mDevice.publish_moteus_frame(positionFrame); - } - - // Position Velocity - // Nan 2.0 = spin at 2 rev/s - // 1.0 0.0 = Stay put at 1 rev round - // Nan 0.0 = Don't move - - auto BrushlessController::setDesiredVelocity(RadiansPerSecond velocity) -> void { - // only check for limit switches if at least one limit switch exists and is enabled - if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { - sendQuery(); - - MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); - if ((velocity > Radians{0} && limitSwitchInfo.isFwdPressed) || (velocity < Radians{0} && limitSwitchInfo.isBwdPressed)) { - setBrake(); - return; - } - } - - - velocity = velocity * mVelocityMultiplier; - - RevolutionsPerSecond velocity_rev_s = std::clamp(velocity, mMinVelocity, mMaxVelocity); - if (abs(velocity_rev_s).get() < 1e-5) { - setBrake(); - } else { - moteus::PositionMode::Command command{ - .position = std::numeric_limits::quiet_NaN(), - .velocity = velocity_rev_s.get(), - .maximum_torque = mMaxTorque, - .watchdog_timeout = mWatchdogTimeout, - }; - - moteus::CanFdFrame positionFrame = mController.MakePosition(command); - mDevice.publish_moteus_frame(positionFrame); - } - } - - auto BrushlessController::setStop() -> void { - moteus::CanFdFrame setStopFrame = mController.MakeStop(); - mDevice.publish_moteus_frame(setStopFrame); - } - - auto BrushlessController::setBrake() -> void { - moteus::CanFdFrame setBrakeFrame = mController.MakeBrake(); - mDevice.publish_moteus_frame(setBrakeFrame); - } - - auto BrushlessController::getPressedLimitSwitchInfo() -> MoteusLimitSwitchInfo { - /* - Testing 2/9: - - Connected limit switch (common is input(black), NC to ground) - - Configured moteus to have all pins set as digital_input and pull_up - - When limit switch not pressed, aux2 = 0xD - - When limit switch pressed, aux1 = 0xF - - Note: has to be active high, so in this scenario we have to flip this bit round. - - This was connected to just one moteus board, not the one with a motor on it. - - Stuff for Limit Switches (from Guthrie) - - Read from config about limit switch settings - - Either 1 or 0 not forward/backward - - - Add a member variable in Brushless.hpp to store limit switch value. Update this limit - switch variable every round in ProcessCANMessage. - */ - // TODO - implement this - MoteusLimitSwitchInfo result{}; - - result.isFwdPressed = false; - result.isBwdPressed = false; - - // TODO do both switch0 and switch1 use aux2? - if (limitSwitch0Present && limitSwitch0Enabled) { - int bitMask = 2; // 0b0010 - bool gpioState = bitMask & moteusAux1Info; - mLimitHit.at(0) = gpioState == limitSwitch0ActiveHigh; - } - if (limitSwitch1Present && limitSwitch1Enabled) { - int bitMask = 2; // 0b0010 - bool gpioState = bitMask & moteusAux2Info; - mLimitHit.at(1) = gpioState == limitSwitch1ActiveHigh; - } - - result.isFwdPressed = (mLimitHit.at(0) && limitSwitch0LimitsFwd) || (mLimitHit.at(1) && limitSwitch1LimitsFwd); - result.isBwdPressed = (mLimitHit.at(0) && !limitSwitch0LimitsFwd) || (mLimitHit.at(1) && !limitSwitch1LimitsFwd); - - if (result.isFwdPressed) { - adjust(limitSwitch0ReadjustPosition); - } - else if (result.isBwdPressed) { - adjust(limitSwitch1ReadjustPosition); - } - - return result; - } - - auto BrushlessController::adjust(Radians commandedPosition) -> void { - Revolutions commandedPosition_rev = std::clamp(commandedPosition, mMinPosition, mMaxPosition); - moteus::OutputExact::Command command{ - .position = commandedPosition_rev.get(), - }; - moteus::OutputExact::Command outputExactCmd{command}; - moteus::CanFdFrame setPositionFrame = mController.MakeOutputExact(outputExactCmd); - mDevice.publish_moteus_frame(setPositionFrame); - } - - auto BrushlessController::sendQuery() -> void { - moteus::Query::Format qFormat{}; - qFormat.aux1_gpio = moteus::kInt8; - qFormat.aux2_gpio = moteus::kInt8; - moteus::CanFdFrame queryFrame = mController.MakeQuery(&qFormat); - mDevice.publish_moteus_frame(queryFrame); - } - - auto BrushlessController::processCANMessage(CAN::ConstPtr const& msg) -> void { - assert(msg->source == mControllerName); - assert(msg->destination == mName); - auto result = moteus::Query::Parse(msg->data.data(), msg->data.size()); - // ROS_INFO("controller: %s %3d p/a/v/t=(%7.3f,%7.3f,%7.3f,%7.3f) v/t/f=(%5.1f,%5.1f,%3d) GPIO: Aux1-%X , Aux2-%X", - // mControllerName.c_str(), - // result.mode, - // result.position, - // result.abs_position, - // result.velocity, - // result.torque, - // result.voltage, - // result.temperature, - // result.fault, - // result.aux1_gpio, - // result.aux2_gpio - // ); - - mCurrentPosition = mrover::Revolutions{result.position}; // moteus stores position in revolutions. - mCurrentVelocity = mrover::RevolutionsPerSecond{result.velocity} / mVelocityMultiplier; // moteus stores position in revolutions. - - mErrorState = moteusErrorCodeToErrorState(result.mode, static_cast(result.fault)); - mState = moteusModeToState(result.mode); - - moteusAux1Info = (result.aux1_gpio) ? result.aux1_gpio : moteusAux1Info; - moteusAux2Info = (result.aux1_gpio) ? result.aux2_gpio : moteusAux2Info; - - if (result.mode == moteus::Mode::kPositionTimeout || result.mode == moteus::Mode::kFault) { - setStop(); - ROS_WARN("Position timeout hit"); - } - } - - auto BrushlessController::getEffort() -> double { - // TODO - need to properly set mMeasuredEFfort elsewhere. - // (Art Boyarov): return quiet_Nan, same as Brushed Controller - return std::numeric_limits::quiet_NaN(); - } - - auto BrushlessController::mapThrottleToVelocity(Percent throttle) const -> RadiansPerSecond { - std::clamp(throttle, -1_percent, 1_percent); - - // Map the throttle to the velocity range - return RadiansPerSecond{(throttle.get() + 1.0f) / 2.0f * (mMaxVelocity.get() - mMinVelocity.get()) + mMinVelocity.get()}; - } - - auto BrushlessController::moteusErrorCodeToErrorState(moteus::Mode motor_mode, ErrorCode motor_error_code) -> std::string { - if (motor_mode != moteus::Mode::kFault) return "No Error"; - switch (motor_error_code) { - case ErrorCode::DmaStreamTransferError: - return "DMA Stream Transfer Error"; - case ErrorCode::DmaStreamFifiError: - return "DMA Stream FIFO Error"; - case ErrorCode::UartOverrunError: - return "UART Overrun Error"; - case ErrorCode::UartFramingError: - return "UART Framing Error"; - case ErrorCode::UartNoiseError: - return "UART Noise Error"; - case ErrorCode::UartBufferOverrunError: - return "UART Buffer Overrun Error"; - case ErrorCode::UartParityError: - return "UART Parity Error"; - case ErrorCode::CalibrationFault: - return "Calibration Fault"; - case ErrorCode::MotorDriverFault: - return "Motor Driver Fault"; - case ErrorCode::OverVoltage: - return "Over Voltage"; - case ErrorCode::EncoderFault: - return "Encoder Fault"; - case ErrorCode::MotorNotConfigured: - return "Motor Not Configured"; - case ErrorCode::PwmCycleOverrun: - return "PWM Cycle Overrun"; - case ErrorCode::OverTemperature: - return "Over Temperature"; - case ErrorCode::StartOutsideLimit: - return "Start Outside Limit"; - case ErrorCode::UnderVoltage: - return "Under Voltage"; - case ErrorCode::ConfigChanged: - return "Configuration Changed"; - case ErrorCode::ThetaInvalid: - return "Theta Invalid"; - case ErrorCode::PositionInvalid: - return "Position Invalid"; - default: - return "Unknown Error"; - } - } - - auto BrushlessController::moteusModeToState(moteus::Mode motor_mode) -> std::string { - switch (motor_mode) { - case moteus::Mode::kStopped: - return "Motor Stopped"; - case moteus::Mode::kFault: - return "Motor Fault"; - case moteus::Mode::kPwm: - return "PWM Operating Mode"; - case moteus::Mode::kVoltage: - return "Voltage Operating Mode"; - case moteus::Mode::kVoltageFoc: - return "Voltage FOC Operating Mode"; - case moteus::Mode::kVoltageDq: - return "Voltage DQ Operating Mode"; - case moteus::Mode::kCurrent: - return "Current Operating Mode"; - case moteus::Mode::kPosition: - return "Position Operating Mode"; - case moteus::Mode::kPositionTimeout: - return "Position Timeout"; - case moteus::Mode::kZeroVelocity: - return "Zero Velocity"; - default: - return "Unknown Mode"; - } - } -} // namespace mrover diff --git a/src/esw/motor_library/brushless.hpp b/src/esw/motor_library/brushless.hpp index eeb036084..fc1437697 100644 --- a/src/esw/motor_library/brushless.hpp +++ b/src/esw/motor_library/brushless.hpp @@ -1,16 +1,10 @@ #pragma once -#include "params_utils.hpp" -#include -#include -#include - -// TODO(quintin) this is not defined in my system can header for some reason, but moteus needs it? Is this the correct value? -#define CANFD_FDF 0x04 #include #include #include +#include namespace mrover { @@ -58,55 +52,369 @@ namespace mrover { }; struct MoteusLimitSwitchInfo { - bool isFwdPressed; - bool isBwdPressed; + bool isFwdPressed{}; + bool isBwdPressed{}; }; - class BrushlessController : public Controller { + template + class BrushlessController final : public ControllerBase> { + using Base = ControllerBase; + + // TODO(quintin): this is actually so dumb + using OutputPosition = typename Base::OutputPosition; + using OutputVelocity = typename Base::OutputVelocity; + + using Base::mControllerName; + using Base::mCurrentPosition; + using Base::mCurrentVelocity; + using Base::mDevice; + using Base::mErrorState; + using Base::mLimitHit; + using Base::mMasterName; + using Base::mNh; + using Base::mState; + public: - BrushlessController(ros::NodeHandle const& nh, std::string name, std::string controllerName); - ~BrushlessController() override = default; - - void setDesiredThrottle(Percent throttle) override; - void setDesiredVelocity(RadiansPerSecond velocity) override; - void setDesiredPosition(Radians position) override; - void processCANMessage(CAN::ConstPtr const& msg) override; - auto getEffort() -> double override; - void setStop(); - void setBrake(); - auto getPressedLimitSwitchInfo() -> MoteusLimitSwitchInfo; - void adjust(Radians position) override; - void sendQuery(); + BrushlessController(ros::NodeHandle const& nh, std::string masterName, std::string controllerName) + : Base{nh, std::move(masterName), std::move(controllerName)} { + + XmlRpc::XmlRpcValue brushlessMotorData; + assert(mNh.hasParam(std::format("brushless_motors/controllers/{}", mControllerName))); + mNh.getParam(std::format("brushless_motors/controllers/{}", mControllerName), brushlessMotorData); + assert(brushlessMotorData.getType() == XmlRpc::XmlRpcValue::TypeStruct); + + mMinVelocity = OutputVelocity{xmlRpcValueToTypeOrDefault(brushlessMotorData, "min_velocity", -1.0)}; + mMaxVelocity = OutputVelocity{xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_velocity", 1.0)}; + + mMinPosition = OutputPosition{xmlRpcValueToTypeOrDefault(brushlessMotorData, "min_position", -1.0)}; + mMaxPosition = OutputPosition{xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_position", 1.0)}; + + mMaxTorque = xmlRpcValueToTypeOrDefault(brushlessMotorData, "max_torque", 0.3); + mWatchdogTimeout = xmlRpcValueToTypeOrDefault(brushlessMotorData, "watchdog_timeout", 0.1); + + limitSwitch0Present = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_present", false); + limitSwitch1Present = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_present", false); + limitSwitch0Enabled = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_enabled", true); + limitSwitch1Enabled = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_enabled", true); + + limitSwitch0LimitsFwd = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_limits_fwd", false); + limitSwitch1LimitsFwd = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_limits_fwd", false); + limitSwitch0ActiveHigh = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_is_active_high", true); + limitSwitch1ActiveHigh = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_is_active_high", true); + limitSwitch0UsedForReadjustment = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_used_for_readjustment", false); + limitSwitch1UsedForReadjustment = xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_used_for_readjustment", false); + limitSwitch0ReadjustPosition = OutputPosition{xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_0_readjust_position", 0.0)}; + limitSwitch1ReadjustPosition = OutputPosition{xmlRpcValueToTypeOrDefault(brushlessMotorData, "limit_1_readjust_position", 0.0)}; + + // if active low, we want to make the default value make it believe that + // the limit switch is NOT pressed. + // This is because we may not receive the newest query message from the moteus + // as a result of either testing or startup. + if (limitSwitch0Present && !limitSwitch0ActiveHigh) { + mMoteusAux2Info |= 0b01; + } + if (limitSwitch1Present) { + mMoteusAux2Info |= 0b10; + } + + moteus::Controller::Options options; + moteus::Query::Format queryFormat; + queryFormat.aux1_gpio = moteus::kInt8; + queryFormat.aux2_gpio = moteus::kInt8; + if (this->isJointDe()) { // add joint de abs slots to CAN message + queryFormat.extra[0] = moteus::Query::ItemFormat{ + .register_number = moteus::Register::kEncoder1Position, + .resolution = moteus::kFloat, + }; + queryFormat.extra[1] = moteus::Query::ItemFormat{ + .register_number = moteus::Register::kEncoder1Velocity, + .resolution = moteus::kFloat, + }; + } + options.query_format = queryFormat; + mMoteus.emplace(options); + } + + auto setDesiredThrottle(Percent throttle) -> void { + setDesiredVelocity(mapThrottleToVelocity(throttle)); + } + + auto setDesiredPosition(OutputPosition position) -> void { + // only check for limit switches if at least one limit switch exists and is enabled + if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { + sendQuery(); + + MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); + if ((mCurrentPosition < position && limitSwitchInfo.isFwdPressed) || (mCurrentPosition > position && limitSwitchInfo.isBwdPressed)) { + setBrake(); + return; + } + } + + position = std::clamp(position, mMinPosition, mMaxPosition); + + moteus::PositionMode::Command command{ + .position = position.get(), + .velocity = 0.0, + .maximum_torque = mMaxTorque, + .watchdog_timeout = mWatchdogTimeout, + }; + if (this->isJointDe()) { + ROS_INFO_STREAM(std::format("Setting position to {}", position.get()).c_str()); + } + moteus::CanFdFrame positionFrame = mMoteus->MakePosition(command); + mDevice.publish_moteus_frame(positionFrame); + } + + auto processCANMessage(CAN::ConstPtr const& msg) -> void { + assert(msg->source == mControllerName); + assert(msg->destination == mMasterName); + auto result = moteus::Query::Parse(msg->data.data(), msg->data.size()); + if (this->isJointDe()) { + ROS_INFO("controller: %s %3d p/a/v/t=(%7.3f,%7.3f,%7.3f,%7.3f) v/t/f=(%5.1f,%5.1f,%3d) GPIO: Aux1-%X , Aux2-%X", + mControllerName.c_str(), + result.mode, + result.position, + result.abs_position, + result.velocity, + result.torque, + result.voltage, + result.temperature, + result.fault, + result.aux1_gpio, + result.aux2_gpio); + } + + if (this->isJointDe()) { + mCurrentPosition = OutputPosition{result.extra[0].value}; // get value of absolute encoder if its joint_de0/1 + mCurrentVelocity = OutputVelocity{result.extra[1].value}; + } else { + mCurrentPosition = OutputPosition{result.position}; // moteus stores position in revolutions. + mCurrentVelocity = OutputVelocity{result.velocity}; // moteus stores position in revolutions. + } + mCurrentEffort = result.torque; + + mErrorState = moteusErrorCodeToErrorState(result.mode, static_cast(result.fault)); + mState = moteusModeToState(result.mode); + + mMoteusAux1Info = result.aux1_gpio; + mMoteusAux2Info = result.aux2_gpio; + + if (result.mode == moteus::Mode::kPositionTimeout || result.mode == moteus::Mode::kFault) { + setStop(); + ROS_WARN("Position timeout hit"); + } + } + + auto setDesiredVelocity(OutputVelocity velocity) -> void { + // only check for limit switches if at least one limit switch exists and is enabled + if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { + sendQuery(); + + MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); + if ((velocity > OutputVelocity{0} && limitSwitchInfo.isFwdPressed) || (velocity < OutputVelocity{0} && limitSwitchInfo.isBwdPressed)) { + setBrake(); + return; + } + } + + velocity = std::clamp(velocity, mMinVelocity, mMaxVelocity); + + if (abs(velocity) < OutputVelocity{1e-5}) { + setBrake(); + } else { + moteus::PositionMode::Command command{ + .position = std::numeric_limits::quiet_NaN(), + .velocity = velocity.get(), + .maximum_torque = mMaxTorque, + .watchdog_timeout = mWatchdogTimeout, + }; + + moteus::CanFdFrame positionFrame = mMoteus->MakePosition(command); + mDevice.publish_moteus_frame(positionFrame); + } + } + + auto getEffort() -> double { + // TODO - need to properly set mMeasuredEFfort elsewhere. + // (Art Boyarov): return quiet_Nan, same as Brushed Controller + return mCurrentEffort; + } + + auto setStop() -> void { + moteus::CanFdFrame setStopFrame = mMoteus->MakeStop(); + mDevice.publish_moteus_frame(setStopFrame); + } + + auto setBrake() -> void { + moteus::CanFdFrame setBrakeFrame = mMoteus->MakeBrake(); + mDevice.publish_moteus_frame(setBrakeFrame); + } + + auto getPressedLimitSwitchInfo() -> MoteusLimitSwitchInfo { + /* + Testing 2/9: + - Connected limit switch (common is input(black), NC to ground) + - Configured moteus to have all pins set as digital_input and pull_up + - When limit switch not pressed, aux2 = 0xD + - When limit switch pressed, aux1 = 0xF + - Note: has to be active high, so in this scenario we have to flip this bit round. + - This was connected to just one moteus board, not the one with a motor on it. + + Stuff for Limit Switches (from Guthrie) + - Read from config about limit switch settings + - Either 1 or 0 not forward/backward + + - Add a member variable in Brushless.hpp to store limit switch value. + pdate this limit switch variable every round in ProcessCANMessage. + + - Note: we can get aux pin info even without sending a query command. + Tested with sending velocity commands. + */ + // TODO - implement this + MoteusLimitSwitchInfo result{}; + result.isFwdPressed = false; + result.isBwdPressed = false; + + // Limit switches now wired to AUX2 (index 0 and 1) + if (limitSwitch0Present && limitSwitch0Enabled) { + bool gpioState = 0b01 & mMoteusAux2Info; + mLimitHit.at(0) = gpioState == limitSwitch0ActiveHigh; + } + if (limitSwitch1Present && limitSwitch1Enabled) { + bool gpioState = 0b10 & mMoteusAux2Info; + mLimitHit.at(1) = gpioState == limitSwitch1ActiveHigh; + } + + result.isFwdPressed = (mLimitHit.at(0) && limitSwitch0LimitsFwd) || (mLimitHit.at(1) && limitSwitch1LimitsFwd); + result.isBwdPressed = (mLimitHit.at(0) && !limitSwitch0LimitsFwd) || (mLimitHit.at(1) && !limitSwitch1LimitsFwd); + + if (result.isFwdPressed) { + adjust(limitSwitch0ReadjustPosition); + } else if (result.isBwdPressed) { + adjust(limitSwitch1ReadjustPosition); + } + + return result; + } + + auto adjust(OutputPosition position) -> void { + position = std::clamp(position, mMinPosition, mMaxPosition); + moteus::OutputExact::Command command{ + .position = position.get(), + }; + moteus::OutputExact::Command outputExactCmd{command}; + moteus::CanFdFrame setPositionFrame = mMoteus->MakeOutputExact(outputExactCmd); + mDevice.publish_moteus_frame(setPositionFrame); + } + + auto sendQuery() -> void { + moteus::CanFdFrame queryFrame = mMoteus->MakeQuery(); + mDevice.publish_moteus_frame(queryFrame); + } private: - moteus::Controller mController{moteus::Controller::Options{}}; + std::optional mMoteus; bool limitSwitch0Present{}; bool limitSwitch1Present{}; - bool limitSwitch0Enabled{true}; - bool limitSwitch1Enabled{true}; - bool limitSwitch0LimitsFwd{false}; - bool limitSwitch1LimitsFwd{false}; - bool limitSwitch0ActiveHigh{true}; - bool limitSwitch1ActiveHigh{true}; + bool limitSwitch0Enabled{}; + bool limitSwitch1Enabled{}; + bool limitSwitch0LimitsFwd{}; + bool limitSwitch1LimitsFwd{}; + bool limitSwitch0ActiveHigh{}; + bool limitSwitch1ActiveHigh{}; bool limitSwitch0UsedForReadjustment{}; bool limitSwitch1UsedForReadjustment{}; - Radians limitSwitch0ReadjustPosition{}; - Radians limitSwitch1ReadjustPosition{}; + OutputPosition limitSwitch0ReadjustPosition{}; + OutputPosition limitSwitch1ReadjustPosition{}; - double mMaxTorque{0.3}; + double mMaxTorque{0.5}; double mWatchdogTimeout{0.1}; - int8_t moteusAux1Info{0}; - int8_t moteusAux2Info{0}; + std::int8_t mMoteusAux1Info{}, mMoteusAux2Info{}; - Radians mMinPosition, mMaxPosition; - RadiansPerSecond mMinVelocity, mMaxVelocity; + OutputPosition mMinPosition, mMaxPosition; + OutputVelocity mMinVelocity, mMaxVelocity; + double mCurrentEffort{std::numeric_limits::quiet_NaN()}; + + [[nodiscard]] auto mapThrottleToVelocity(Percent throttle) const -> OutputVelocity { + throttle = std::clamp(throttle, -1_percent, 1_percent); + return abs(throttle) * (throttle > 0_percent ? mMaxVelocity : mMinVelocity); + } - // Function to map throttle to velocity - [[nodiscard]] auto mapThrottleToVelocity(Percent throttle) const -> RadiansPerSecond; // Converts moteus error codes and mode codes to std::string descriptions - static auto moteusErrorCodeToErrorState(moteus::Mode motor_mode, ErrorCode motor_error_code) -> std::string; - static auto moteusModeToState(moteus::Mode motor_mode) -> std::string; + static auto moteusErrorCodeToErrorState(moteus::Mode motor_mode, ErrorCode motor_error_code) -> std::string { + if (motor_mode != moteus::Mode::kFault) return "No Error"; + switch (motor_error_code) { + case ErrorCode::DmaStreamTransferError: + return "DMA Stream Transfer Error"; + case ErrorCode::DmaStreamFifiError: + return "DMA Stream FIFO Error"; + case ErrorCode::UartOverrunError: + return "UART Overrun Error"; + case ErrorCode::UartFramingError: + return "UART Framing Error"; + case ErrorCode::UartNoiseError: + return "UART Noise Error"; + case ErrorCode::UartBufferOverrunError: + return "UART Buffer Overrun Error"; + case ErrorCode::UartParityError: + return "UART Parity Error"; + case ErrorCode::CalibrationFault: + return "Calibration Fault"; + case ErrorCode::MotorDriverFault: + return "Motor Driver Fault"; + case ErrorCode::OverVoltage: + return "Over Voltage"; + case ErrorCode::EncoderFault: + return "Encoder Fault"; + case ErrorCode::MotorNotConfigured: + return "Motor Not Configured"; + case ErrorCode::PwmCycleOverrun: + return "PWM Cycle Overrun"; + case ErrorCode::OverTemperature: + return "Over Temperature"; + case ErrorCode::StartOutsideLimit: + return "Start Outside Limit"; + case ErrorCode::UnderVoltage: + return "Under Voltage"; + case ErrorCode::ConfigChanged: + return "Configuration Changed"; + case ErrorCode::ThetaInvalid: + return "Theta Invalid"; + case ErrorCode::PositionInvalid: + return "Position Invalid"; + default: + return "Unknown Error"; + } + } + + static auto moteusModeToState(moteus::Mode motor_mode) -> std::string { + switch (motor_mode) { + case moteus::Mode::kStopped: + return "Motor Stopped"; + case moteus::Mode::kFault: + return "Motor Fault"; + case moteus::Mode::kPwm: + return "PWM Operating Mode"; + case moteus::Mode::kVoltage: + return "Voltage Operating Mode"; + case moteus::Mode::kVoltageFoc: + return "Voltage FOC Operating Mode"; + case moteus::Mode::kVoltageDq: + return "Voltage DQ Operating Mode"; + case moteus::Mode::kCurrent: + return "Current Operating Mode"; + case moteus::Mode::kPosition: + return "Position Operating Mode"; + case moteus::Mode::kPositionTimeout: + return "Position Timeout"; + case moteus::Mode::kZeroVelocity: + return "Zero Velocity"; + default: + return "Unknown Mode"; + } + } }; } // namespace mrover diff --git a/src/esw/motor_library/controller.hpp b/src/esw/motor_library/controller.hpp index c19fc0049..a608cd46f 100644 --- a/src/esw/motor_library/controller.hpp +++ b/src/esw/motor_library/controller.hpp @@ -7,10 +7,12 @@ #include #include #include +#include #include #include #include +#include #include #include #include @@ -18,74 +20,100 @@ namespace mrover { - class Controller { + // This uses CRTP to allow for static polymorphism + // See: https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern + template + class ControllerBase { public: - Controller(ros::NodeHandle const& nh, std::string name, std::string controllerName) + using OutputPosition = TOutputPosition; + using OutputVelocity = compound_unit>; + + ControllerBase(ros::NodeHandle const& nh, std::string masterName, std::string controllerName) : mNh{nh}, - mName{std::move(name)}, + mMasterName{std::move(masterName)}, mControllerName{std::move(controllerName)}, - mDevice{nh, mName, mControllerName}, - mIncomingCANSub{ - mNh.subscribe( - std::format("can/{}/in", mControllerName), 16, &Controller::processCANMessage, this)} { - // Subscribe to the ROS topic for commands - mMoveThrottleSub = mNh.subscribe(std::format("{}_throttle_cmd", mControllerName), 1, &Controller::moveMotorsThrottle, this); - mMoveVelocitySub = mNh.subscribe(std::format("{}_velocity_cmd", mControllerName), 1, &Controller::moveMotorsVelocity, this); - mMovePositionSub = mNh.subscribe(std::format("{}_position_cmd", mControllerName), 1, &Controller::moveMotorsPosition, this); + mDevice{mNh, mMasterName, mControllerName}, + mIncomingCANSub{mNh.subscribe(std::format("can/{}/in", mControllerName), 16, &ControllerBase::processCANMessage, this)}, + mMoveThrottleSub{mNh.subscribe(std::format("{}_throttle_cmd", mControllerName), 1, &ControllerBase::setDesiredThrottle, this)}, + mMoveVelocitySub{mNh.subscribe(std::format("{}_velocity_cmd", mControllerName), 1, &ControllerBase::setDesiredVelocity, this)}, + mMovePositionSub{mNh.subscribe(std::format("{}_position_cmd", mControllerName), 1, &ControllerBase::setDesiredPosition, this)}, + // mAdjustEncoderSub{mNh.subscribe(std::format("{}_adjust_cmd", mControllerName), 1, &ControllerBase::adjustEncoder, this)}, + mJointDataPub{mNh.advertise(std::format("{}_joint_data", mControllerName), 1)}, + mControllerDataPub{mNh.advertise(std::format("{}_controller_data", mControllerName), 1)}, + mPublishDataTimer{mNh.createTimer(ros::Duration{0.1}, &ControllerBase::publishDataCallback, this)}, + mAdjustServer{mNh.advertiseService(std::format("{}_adjust", mControllerName), &ControllerBase::adjustServiceCallback, this)} { + } - mJointDataPub = mNh.advertise(std::format("{}_joint_data", mControllerName), 1); - mControllerDataPub = mNh.advertise(std::format("{}_controller_data", mControllerName), 1); + ControllerBase(ControllerBase const&) = delete; + ControllerBase(ControllerBase&&) = delete; - mPublishDataTimer = mNh.createTimer(ros::Duration(0.1), &Controller::publishDataCallback, this); + auto operator=(ControllerBase const&) -> ControllerBase& = delete; + auto operator=(ControllerBase&&) -> ControllerBase& = delete; - mAdjustServer = mNh.advertiseService(std::format("{}_adjust", mControllerName), &Controller::adjustServiceCallback, this); + // TODO(quintin): Why can't I bind directly to &Derived::processCANMessage? + auto processCANMessage(CAN::ConstPtr const& msg) -> void { + static_cast(this)->processCANMessage(msg); } - virtual ~Controller() = default; - - virtual void setDesiredThrottle(Percent throttle) = 0; // from -1.0 to 1.0 - virtual void setDesiredVelocity(RadiansPerSecond velocity) = 0; // joint output - virtual void setDesiredPosition(Radians position) = 0; // joint output - virtual void processCANMessage(CAN::ConstPtr const& msg) = 0; - virtual double getEffort() = 0; - virtual void adjust(Radians position) = 0; - - void moveMotorsThrottle(Throttle::ConstPtr const& msg) { + auto setDesiredThrottle(Throttle::ConstPtr const& msg) -> void { if (msg->names.size() != 1 || msg->names.at(0) != mControllerName || msg->throttles.size() != 1) { ROS_ERROR("Throttle request at topic for %s ignored!", msg->names.at(0).c_str()); return; } - setDesiredThrottle(msg->throttles.at(0)); + static_cast(this)->setDesiredThrottle(msg->throttles.front()); } - - void moveMotorsVelocity(Velocity::ConstPtr const& msg) { + auto setDesiredVelocity(Velocity::ConstPtr const& msg) -> void { if (msg->names.size() != 1 || msg->names.at(0) != mControllerName || msg->velocities.size() != 1) { ROS_ERROR("Velocity request at topic for %s ignored!", msg->names.at(0).c_str()); return; } - setDesiredVelocity(RadiansPerSecond{msg->velocities.at(0)}); + // ROS message will always be in SI units with no conversions + using Velocity = typename detail::strip_conversion::type; + OutputVelocity velocity = Velocity{msg->velocities.front()}; + static_cast(this)->setDesiredVelocity(velocity); } - void moveMotorsPosition(Position::ConstPtr const& msg) { + auto setDesiredPosition(Position::ConstPtr const& msg) -> void { if (msg->names.size() != 1 || msg->names.at(0) != mControllerName || msg->positions.size() != 1) { ROS_ERROR("Position request at topic for %s ignored!", msg->names.at(0).c_str()); return; } - setDesiredPosition(Radians{msg->positions.at(0)}); + // ROS message will always be in SI units with no conversions + using Position = typename detail::strip_conversion::type; + OutputPosition position = Position{msg->positions.front()}; + static_cast(this)->setDesiredPosition(position); + } + + auto adjustEncoder(MotorsAdjust::ConstPtr const& msg) -> void { + if (msg->names.size() != 1 || msg->names.at(0) != mControllerName || msg->values.size() != 1) { + ROS_ERROR("Adjust request at topic for %s ignored!", msg->names.at(0).c_str()); + return; + } + + using Position = typename detail::strip_conversion::type; + OutputPosition position = Position{msg->values.front()}; + static_cast(this)->adjust(position); + } + + [[nodiscard]] auto isJointDe() const -> bool { + return mControllerName == "joint_de_0" || mControllerName == "joint_de_1"; } auto publishDataCallback(ros::TimerEvent const&) -> void { { + using Position = typename detail::strip_conversion::type; + using Velocity = typename detail::strip_conversion::type; + sensor_msgs::JointState jointState; jointState.header.stamp = ros::Time::now(); jointState.name = {mControllerName}; - jointState.position = {mCurrentPosition.get()}; - jointState.velocity = {mCurrentVelocity.get()}; - jointState.effort = {getEffort()}; + jointState.position = {Position{mCurrentPosition}.get()}; + jointState.velocity = {Velocity{mCurrentVelocity}.get()}; + jointState.effort = {static_cast(this)->getEffort()}; mJointDataPub.publish(jointState); } { @@ -103,28 +131,30 @@ namespace mrover { } } - bool adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) { + auto adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) -> bool { if (req.name != mControllerName) { ROS_ERROR("Adjust request at server for %s ignored", req.name.c_str()); res.success = false; return true; } - adjust(Radians{req.value}); + + using Position = typename detail::strip_conversion::type; + OutputPosition position = Position{req.value}; + static_cast(this)->adjust(position); res.success = true; return true; } protected: - Dimensionless mVelocityMultiplier; ros::NodeHandle mNh; - std::string mName, mControllerName; + std::string mMasterName, mControllerName; CanDevice mDevice; ros::Subscriber mIncomingCANSub; - Radians mCurrentPosition{}; - RadiansPerSecond mCurrentVelocity{}; + OutputPosition mCurrentPosition{}; + OutputVelocity mCurrentVelocity{}; Percent mCalibrationThrottle{}; bool mIsCalibrated{}; - bool mhasLimit{}; + bool mHasLimit{}; std::string mErrorState; std::string mState; std::array mLimitHit{}; @@ -132,6 +162,7 @@ namespace mrover { ros::Subscriber mMoveThrottleSub; ros::Subscriber mMoveVelocitySub; ros::Subscriber mMovePositionSub; + ros::Subscriber mAdjustEncoderSub; ros::Publisher mJointDataPub; ros::Publisher mControllerDataPub; ros::Timer mPublishDataTimer; diff --git a/src/esw/motor_library/motors_group.cpp b/src/esw/motor_library/motors_group.cpp index 97a26ba88..2594d4edc 100644 --- a/src/esw/motor_library/motors_group.cpp +++ b/src/esw/motor_library/motors_group.cpp @@ -52,19 +52,27 @@ namespace mrover { for (std::string const& name: mControllerNames) { if (!controllersRoot.hasMember(name)) { - ROS_ERROR("There is a mismatch in the config - motor %s doesn't exist!", name.c_str()); + ROS_ERROR_STREAM(std::format("There is a mismatch in the config - motor {} doesn't exist!", name)); throw; } auto type = xmlRpcValueToTypeOrDefault(controllersRoot[name], "type"); - assert(type == "brushed" || type == "brushless"); + if (!(type == "brushed" || type == "brushless" || type == "brushless_linear")) { + ROS_ERROR_STREAM(std::format("Unknown motor type %s!", type)); + throw; + } // TODO: avoid hard coding Jetson here - can move into constructor of MotorsGroup // and let the bridge nodes hardcode as jetson. if (type == "brushed") { - mControllers.emplace(name, std::make_unique(mNh, "jetson", name)); + mControllers.try_emplace(name, std::in_place_type, mNh, "jetson", name); } else if (type == "brushless") { - mControllers.emplace(name, std::make_unique(mNh, "jetson", name)); + mControllers.try_emplace(name, std::in_place_type>, mNh, "jetson", name); + } else if (type == "brushless_linear") { + mControllers.try_emplace(name, std::in_place_type>, mNh, "jetson", name); + } else { + ROS_ERROR_STREAM(std::format("Unknown motor type %s!", type)); + throw; } } @@ -76,8 +84,8 @@ namespace mrover { mJointDataPub = mNh.advertise(std::format("{}_joint_data", mGroupName), 1); } - auto MotorsGroup::getController(std::string const& name) const -> Controller& { - return *mControllers.at(name); + auto MotorsGroup::getController(std::string const& name) -> Controller& { + return mControllers.at(name); } auto MotorsGroup::moveMotorsThrottle(Throttle::ConstPtr const& msg) -> void { diff --git a/src/esw/motor_library/motors_group.hpp b/src/esw/motor_library/motors_group.hpp index 1f9f1a3ed..edec2dbaf 100644 --- a/src/esw/motor_library/motors_group.hpp +++ b/src/esw/motor_library/motors_group.hpp @@ -5,22 +5,32 @@ #include #include -#include +#include +#include #include #include #include #include +#include namespace mrover { + using Controller = std::variant, BrushlessController>; + class MotorsGroup { public: MotorsGroup() = default; + MotorsGroup(MotorsGroup const&) = delete; + MotorsGroup(MotorsGroup&&) = delete; + + auto operator=(MotorsGroup const&) -> MotorsGroup& = delete; + auto operator=(MotorsGroup&&) -> MotorsGroup& = delete; + MotorsGroup(ros::NodeHandle const& nh, std::string groupName); - auto getController(std::string const& name) const -> Controller&; + auto getController(std::string const& name) -> Controller&; auto moveMotorsThrottle(Throttle::ConstPtr const& msg) -> void; @@ -38,6 +48,7 @@ namespace mrover { ros::Subscriber mMoveThrottleSub; ros::Subscriber mMoveVelocitySub; ros::Subscriber mMovePositionSub; + ros::Publisher mJointDataPub; ros::Publisher mControllerDataPub; @@ -46,9 +57,10 @@ namespace mrover { std::unordered_map mPositionPubsByName; std::unordered_map mJointDataSubsByName; std::unordered_map mControllerDataSubsByName; + std::unordered_map mIndexByName; - std::unordered_map> mControllers; + std::map mControllers; std::string mGroupName; std::vector mControllerNames; diff --git a/src/esw/sa_hw_bridge/main.cpp b/src/esw/sa_bridge/main.cpp similarity index 94% rename from src/esw/sa_hw_bridge/main.cpp rename to src/esw/sa_bridge/main.cpp index 0027684d0..ddfd6a01e 100644 --- a/src/esw/sa_hw_bridge/main.cpp +++ b/src/esw/sa_bridge/main.cpp @@ -9,7 +9,7 @@ auto main(int argc, char** argv) -> int { ros::NodeHandle nh; // Load motor controllers configuration from the ROS parameter server - [[maybe_unused]] auto SAManager = std::make_unique(nh, "sa_hw"); + [[maybe_unused]] auto SAManager = std::make_unique(nh, "sa"); // Enter the ROS event loop ros::spin(); diff --git a/src/esw/sa_translator_bridge/main.cpp b/src/esw/sa_translator_bridge/main.cpp deleted file mode 100644 index 3f2eb58f3..000000000 --- a/src/esw/sa_translator_bridge/main.cpp +++ /dev/null @@ -1,18 +0,0 @@ -#include "sa_translator.hpp" - -#include - -#include - -auto main(int argc, char** argv) -> int { - // Initialize the ROS node - ros::init(argc, argv, "sa_translator_bridge"); - ros::NodeHandle nh; - - [[maybe_unused]] auto saTranslator = std::make_unique(nh); - - // Enter the ROS event loop - ros::spin(); - - return EXIT_SUCCESS; -} \ No newline at end of file diff --git a/src/esw/sa_translator_bridge/sa_translator.cpp b/src/esw/sa_translator_bridge/sa_translator.cpp deleted file mode 100644 index b146c5930..000000000 --- a/src/esw/sa_translator_bridge/sa_translator.cpp +++ /dev/null @@ -1,101 +0,0 @@ - -#include "sa_translator.hpp" - -namespace mrover { - - SATranslator::SATranslator(ros::NodeHandle& nh) { - - - mXAxisMult = requireParamAsUnit(nh, "brushed_motors/controllers/sa_x/rad_to_meters_ratio"); - mYAxisMult = requireParamAsUnit(nh, "brushed_motors/controllers/sa_y/rad_to_meters_ratio"); - mZAxisMult = requireParamAsUnit(nh, "brushless_motors/controllers/sa_z/rad_to_meters_ratio"); - - mThrottleSub = nh.subscribe("sa_throttle_cmd", 1, &SATranslator::processThrottleCmd, this); - mVelocitySub = nh.subscribe("sa_velocity_cmd", 1, &SATranslator::processVelocityCmd, this); - mPositionSub = nh.subscribe("sa_position_cmd", 1, &SATranslator::processPositionCmd, this); - mSAHWJointDataSub = nh.subscribe("sa_hw_joint_data", 1, &SATranslator::processSAHWJointData, this); - - mThrottlePub = std::make_unique(nh.advertise("sa_hw_throttle_cmd", 1)); - mVelocityPub = std::make_unique(nh.advertise("sa_hw_velocity_cmd", 1)); - mPositionPub = std::make_unique(nh.advertise("sa_hw_position_cmd", 1)); - mJointDataPub = std::make_unique(nh.advertise("sa_joint_data", 1)); - } - - - void SATranslator::processThrottleCmd(Throttle::ConstPtr const& msg) { - mThrottlePub->publish(*msg); - } - - - void SATranslator::processVelocityCmd(Velocity::ConstPtr const& msg) { - if (mSAHWNames != msg->names || mSAHWNames.size() != msg->velocities.size()) { - ROS_ERROR("Velocity requests for SA is ignored!"); - return; - } - - Velocity velocity = *msg; - - // joint a convert linear velocity (meters/s) to revolution/s - auto x_axis_vel = convertLinVel(msg->velocities.at(mXAxisIndex), mXAxisMult.get()); - velocity.velocities.at(mXAxisIndex) = x_axis_vel; - - auto y_axis_vel = convertLinVel(msg->velocities.at(mYAxisIndex), mYAxisMult.get()); - velocity.velocities.at(mYAxisIndex) = y_axis_vel; - - auto z_axis_vel = convertLinVel(msg->velocities.at(mZAxisIndex), mZAxisMult.get()); - velocity.velocities.at(mZAxisIndex) = z_axis_vel; - - mVelocityPub->publish(velocity); - } - - - void SATranslator::processPositionCmd(Position::ConstPtr const& msg) { - if (mSAHWNames != msg->names || mSAHWNames.size() != msg->positions.size()) { - ROS_ERROR("Position requests for SA is ignored!"); - return; - } - - Position position = *msg; - - // joint a convert linear velocity (meters/s) to revolution/s - auto x_axis_pos = convertLinPos(msg->positions.at(mXAxisIndex), mXAxisMult.get()); - position.positions.at(mXAxisIndex) = x_axis_pos; - - auto y_axis_pos = convertLinPos(msg->positions.at(mYAxisIndex), mYAxisMult.get()); - position.positions.at(mYAxisIndex) = y_axis_pos; - - auto z_axis_pos = convertLinPos(msg->positions.at(mZAxisIndex), mZAxisMult.get()); - position.positions.at(mZAxisIndex) = z_axis_pos; - - mPositionPub->publish(position); - } - - void SATranslator::processSAHWJointData(sensor_msgs::JointState::ConstPtr const& msg) { - if (mSAHWNames != msg->name || mSAHWNames.size() != msg->position.size() || mSAHWNames.size() != msg->velocity.size() || mSAHWNames.size() != msg->effort.size()) { - ROS_ERROR("Position requests for SA is ignored!"); - return; - } - - // Convert joint state of joint a from radians/revolutions to meters - auto xAxisLinVel = convertLinVel(static_cast(msg->velocity.at(mXAxisIndex)), mXAxisMult.get()); - auto xAxisLinPos = convertLinPos(static_cast(msg->position.at(mXAxisIndex)), mXAxisMult.get()); - - auto yAxisLinVel = convertLinVel(static_cast(msg->velocity.at(mYAxisIndex)), mYAxisMult.get()); - auto yAxisLinPos = convertLinPos(static_cast(msg->position.at(mYAxisIndex)), mYAxisMult.get()); - - auto zAxisLinVel = convertLinVel(static_cast(msg->velocity.at(mZAxisIndex)), mZAxisMult.get()); - auto zAxisLinPos = convertLinPos(static_cast(msg->position.at(mZAxisIndex)), mZAxisMult.get()); - - sensor_msgs::JointState jointState = *msg; - jointState.velocity.at(mXAxisIndex) = xAxisLinVel; - jointState.position.at(mXAxisIndex) = xAxisLinPos; - jointState.velocity.at(mXAxisIndex) = yAxisLinVel; - jointState.position.at(mXAxisIndex) = yAxisLinPos; - jointState.velocity.at(mXAxisIndex) = zAxisLinVel; - jointState.position.at(mXAxisIndex) = zAxisLinPos; - - - mJointDataPub->publish(jointState); - } - -} // namespace mrover diff --git a/src/esw/sa_translator_bridge/sa_translator.hpp b/src/esw/sa_translator_bridge/sa_translator.hpp deleted file mode 100644 index 86c7925bc..000000000 --- a/src/esw/sa_translator_bridge/sa_translator.hpp +++ /dev/null @@ -1,62 +0,0 @@ -#pragma once - -#include -#include - -#include -#include - -#include "units/units.hpp" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -namespace mrover { - - class SATranslator { - public: - SATranslator() = default; - - SATranslator(ros::NodeHandle& nh); - - void processVelocityCmd(Velocity::ConstPtr const& msg); - - void processPositionCmd(Position::ConstPtr const& msg); - - void processThrottleCmd(Throttle::ConstPtr const& msg); - - void processSAHWJointData(sensor_msgs::JointState::ConstPtr const& msg); - - private: - - const std::vector mSAHWNames = {"sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"}; - std::unique_ptr mThrottlePub; - std::unique_ptr mVelocityPub; - std::unique_ptr mPositionPub; - std::unique_ptr mJointDataPub; - - const size_t mXAxisIndex = std::find(mSAHWNames.begin(), mSAHWNames.end(), "sa_x") - mSAHWNames.begin(); - const size_t mYAxisIndex = std::find(mSAHWNames.begin(), mSAHWNames.end(), "sa_y") - mSAHWNames.begin(); - const size_t mZAxisIndex = std::find(mSAHWNames.begin(), mSAHWNames.end(), "sa_z") - mSAHWNames.begin(); - - RadiansPerMeter mXAxisMult{}; - RadiansPerMeter mYAxisMult{}; - RadiansPerMeter mZAxisMult{}; - - ros::Subscriber mThrottleSub; - ros::Subscriber mVelocitySub; - ros::Subscriber mPositionSub; - ros::Subscriber mSAHWJointDataSub; - - }; - -} // namespace mrover diff --git a/src/esw/science_bridge/main.cpp b/src/esw/science_bridge/main.cpp index cbc35d87b..7f64f9472 100644 --- a/src/esw/science_bridge/main.cpp +++ b/src/esw/science_bridge/main.cpp @@ -29,11 +29,15 @@ auto enableScienceDeviceCallback(std_srvs::SetBool::Request& req, std_srvs::SetB scienceCanDevice->publish_message(mrover::InBoundScienceMessage{mrover::EnableScienceDeviceCommand{.science_device = scienceDevice, .enable = static_cast(req.data)}}); res.success = true; res.message = "DONE"; + + ROS_INFO("Turning on device"); return true; } void processMessage(mrover::HeaterStateData const& message) { + // ROS_ERROR("heater!"); mrover::HeaterData heaterData; + // TODO - this crashes program! heaterData.state.resize(6); for (int i = 0; i < 6; ++i) { heaterData.state.at(i) = GET_BIT_AT_INDEX(message.heater_state_info.on, i); @@ -53,6 +57,7 @@ void processMessage(mrover::SpectralData const& message) { } void processMessage(mrover::ThermistorData const& message) { + // ROS_ERROR("Thermistors!"); mrover::ScienceThermistors scienceThermistors; scienceThermistors.temps.resize(6); for (int i = 0; i < 6; ++i) { @@ -63,6 +68,8 @@ void processMessage(mrover::ThermistorData const& message) { void processCANData(mrover::CAN::ConstPtr const& msg) { + // TODO - fix in future + // ROS_ERROR("Source: %s Destination: %s", msg->source.c_str(), msg->destination.c_str()); assert(msg->source == "science"); assert(msg->destination == "jetson"); diff --git a/src/esw/science_test_bridge/science_test_bridge.cpp b/src/esw/science_test_bridge/science_test_bridge.cpp new file mode 100644 index 000000000..82d987277 --- /dev/null +++ b/src/esw/science_test_bridge/science_test_bridge.cpp @@ -0,0 +1,59 @@ +#include +#include +#include +#include + +int main(int argc, char** argv) { + ros::init(argc, argv, "science_test_bridge"); + ros::NodeHandle nh; + + // List of heater names + std::vector heater_names = {"heater_b0", "heater_n0", "heater_b1", "heater_n1", "heater_b2", "heater_n2", + "uv_led_0", "uv_led_1", "uv_led_2", "white_led_0", "white_led_1", "white_led_2", + }; + + // Create a service message + std_srvs::SetBool srv; + + // Iterate through each heater name and call the service + for (const auto& heater_name : heater_names) { + // Create a ROS service client for the current heater + ros::ServiceClient client = nh.serviceClient("science_enable_" + heater_name); + + // Wait for the service to become available + ros::service::waitForService("science_enable_" + heater_name); + + + float incrementing_time = 0.25f; + float time = 0.0f; + ROS_INFO_STREAM(heater_name << " CAN message sent to turn on. \n\nNow waiting 3 seconds. \n" << heater_name << " should automatically turn off after 1 second in watchdog.\n"); + while (time < 6.0f) { + // Turn the heater on + srv.request.data = true; + client.call(srv); + + ros::Duration(incrementing_time).sleep(); + time += incrementing_time; + + } + + ROS_INFO_STREAM(heater_name << " should have turned off!! \n"); + + // Wait for a few seconds + ros::Duration(3.0).sleep(); + + // Turn the heater off + srv.request.data = false; + if (client.call(srv)) { + ROS_INFO_STREAM(heater_name << " CAN message sent to turn off"); + } else { + ROS_ERROR_STREAM("Failed to call service to turn " << heater_name << " off"); + return 1; + } + + ROS_INFO_STREAM("Waiting 2 seconds before starting again. \n"); + ros::Duration(2.0).sleep(); + } + + return 0; +} diff --git a/src/perception/tag_detector/zed/pch.hpp b/src/perception/tag_detector/zed/pch.hpp index 324b7c7a5..7adb06d71 100644 --- a/src/perception/tag_detector/zed/pch.hpp +++ b/src/perception/tag_detector/zed/pch.hpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include diff --git a/src/preload/format b/src/preload/format index 3176bfefe..b05dc0169 100644 --- a/src/preload/format +++ b/src/preload/format @@ -1,9 +1,10 @@ #pragma once +#ifdef __APPLE__ + // macOS does not have std::format yet // So we define it and redirect it to fmt::format -#ifdef __APPLE__ #include namespace std { @@ -12,6 +13,9 @@ namespace std { return fmt::format(fmt, std::forward(args)...); } } // namespace std + #else + #include_next + #endif diff --git a/src/preload/linux/can.h b/src/preload/linux/can.h new file mode 100644 index 000000000..b4387146a --- /dev/null +++ b/src/preload/linux/can.h @@ -0,0 +1,9 @@ +#pragma once + +#ifndef __APPLE__ + +// These are just stubs to make the code compile (NOT WORK) on macOS + +#include_next + +#endif diff --git a/src/preload/linux/can/raw.h b/src/preload/linux/can/raw.h new file mode 100644 index 000000000..800b140e0 --- /dev/null +++ b/src/preload/linux/can/raw.h @@ -0,0 +1,9 @@ +#pragma once + +#ifndef __APPLE__ + +// These are just stubs to make the code compile (NOT WORK) on macOS + +#include_next + +#endif \ No newline at end of file diff --git a/src/preload/linux/serial.h b/src/preload/linux/serial.h new file mode 100644 index 000000000..eca28ec26 --- /dev/null +++ b/src/preload/linux/serial.h @@ -0,0 +1,37 @@ +#pragma once + +#ifdef __APPLE__ + +// These are just stubs to make the code compile (NOT WORK) on macOS + +struct serial_struct { + int type; + int line; + unsigned int port; + int irq; + int flags; + int xmit_fifo_size; + int custom_divisor; + int baud_base; + unsigned short close_delay; + char io_type; + char reserved_char[1]; + int hub6; + unsigned short closing_wait; /* time to wait before closing */ + unsigned short closing_wait2; /* no longer used... */ + unsigned char* iomem_base; + unsigned short iomem_reg_shift; + unsigned int port_high; + unsigned long iomap_base; /* cookie passed into ioremap */ +}; + +constexpr int TIOCGSERIAL = 0x0000541E; +constexpr int TIOCSSERIAL = 0x0000541F; + +constexpr int ASYNC_LOW_LATENCY = 0x00000020; + +#else + +#include_next + +#endif \ No newline at end of file diff --git a/src/preload/poll.h b/src/preload/poll.h new file mode 100644 index 000000000..450530360 --- /dev/null +++ b/src/preload/poll.h @@ -0,0 +1,13 @@ +#pragma once + +#include_next + +#ifdef __APPLE__ + +// These are just stubs to make the code compile (NOT WORK) on macOS + +inline auto ppoll(pollfd*, nfds_t, timespec const*, sigset_t const*) -> int { + throw std::runtime_error("ppoll is not implemented on macOS"); +} + +#endif diff --git a/src/simulator/mrover_logo.png b/src/simulator/mrover_logo.png new file mode 100644 index 000000000..fd775c037 --- /dev/null +++ b/src/simulator/mrover_logo.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:035377f84792de3a3627d02dbbdc00277b96cad383202a7a7a3af28e380d7aee +size 51577 diff --git a/src/simulator/simulator.controls.cpp b/src/simulator/simulator.controls.cpp index b4436e740..f46cff1df 100644 --- a/src/simulator/simulator.controls.cpp +++ b/src/simulator/simulator.controls.cpp @@ -81,7 +81,6 @@ namespace mrover { if (key == mToggleCameraLockKey) { if (mCameraInRoverTarget) { mCameraInRoverTarget = std::nullopt; - Eigen::Matrix3d rotationMatrix = mCameraInWorld.transform().block<3, 3>(0, 0); Eigen::Vector3d left = rotationMatrix.col(1); diff --git a/src/simulator/simulator.cpp b/src/simulator/simulator.cpp index f7014f3cb..09cbefee9 100644 --- a/src/simulator/simulator.cpp +++ b/src/simulator/simulator.cpp @@ -22,6 +22,7 @@ namespace mrover { mMotorStatusPub = mNh.advertise("/drive_status", 1); mDriveControllerStatePub = mNh.advertise("/drive_controller_data", 1); mArmControllerStatePub = mNh.advertise("/arm_controller_data", 1); + mArmJointStatePub = mNh.advertise("/arm_joint_states", 1); mIkTargetPub = mNh.advertise("/arm_ik", 1); diff --git a/src/simulator/simulator.hpp b/src/simulator/simulator.hpp index c0b3efd07..9565c14db 100644 --- a/src/simulator/simulator.hpp +++ b/src/simulator/simulator.hpp @@ -215,6 +215,7 @@ namespace mrover { ros::Publisher mMotorStatusPub; ros::Publisher mDriveControllerStatePub; ros::Publisher mArmControllerStatePub; + ros::Publisher mArmJointStatePub; tf2_ros::Buffer mTfBuffer; tf2_ros::TransformListener mTfListener{mTfBuffer}; @@ -354,6 +355,12 @@ namespace mrover { ~SimulatorNodelet() override; + SimulatorNodelet(SimulatorNodelet const&) = delete; + SimulatorNodelet(SimulatorNodelet&&) = delete; + + auto operator=(SimulatorNodelet const&) -> SimulatorNodelet& = delete; + auto operator=(SimulatorNodelet&&) -> SimulatorNodelet& = delete; + auto initWindow() -> void; auto initRender() -> void; diff --git a/src/simulator/simulator.sensors.cpp b/src/simulator/simulator.sensors.cpp index b093c72a0..187ad89ea 100644 --- a/src/simulator/simulator.sensors.cpp +++ b/src/simulator/simulator.sensors.cpp @@ -258,6 +258,16 @@ namespace mrover { armControllerState.limit_hit.push_back(limitSwitches); } mArmControllerStatePub.publish(armControllerState); + + sensor_msgs::JointState jointState; + jointState.header.stamp = ros::Time::now(); + for (auto& linkName: {"arm_a_link", "arm_b_link", "arm_c_link", "arm_d_link", "arm_e_link"}) { + jointState.name.push_back(armMsgToUrdf.backward(linkName).value()); + jointState.position.push_back(rover.physics->getJointPos(rover.linkNameToMeta.at(linkName).index)); + jointState.velocity.push_back(rover.physics->getJointVel(rover.linkNameToMeta.at(linkName).index)); + jointState.effort.push_back(rover.physics->getJointTorque(rover.linkNameToMeta.at(linkName).index)); + } + mArmJointStatePub.publish(jointState); } } diff --git a/src/teleoperation/backend/consumers.py b/src/teleoperation/backend/consumers.py index a66111343..d5bc057b8 100644 --- a/src/teleoperation/backend/consumers.py +++ b/src/teleoperation/backend/consumers.py @@ -42,7 +42,6 @@ from backend.models import AutonWaypoint, BasicWaypoint - DEFAULT_ARM_DEADZONE = 0.15 @@ -258,9 +257,9 @@ def handle_controls_message(self, msg): SA_NAMES = ["sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"] RA_NAMES = self.RA_NAMES ra_slow_mode = False - raw_left_trigger = msg["axes"][self.xbox_mappings["left_trigger"]] + raw_left_trigger = msg["buttons"][self.xbox_mappings["left_trigger"]] left_trigger = raw_left_trigger if raw_left_trigger > 0 else 0 - raw_right_trigger = msg["axes"][self.xbox_mappings["right_trigger"]] + raw_right_trigger = msg["buttons"][self.xbox_mappings["right_trigger"]] right_trigger = raw_right_trigger if raw_right_trigger > 0 else 0 arm_pubs = [self.arm_position_cmd_pub, self.arm_velocity_cmd_pub, self.arm_throttle_cmd_pub, self.arm_ik_pub] sa_pubs = [self.sa_position_cmd_pub, self.sa_velocity_cmd_pub, self.sa_throttle_cmd_pub] @@ -367,8 +366,6 @@ def handle_controls_message(self, msg): * self.filter_xbox_button(msg["buttons"], "right_bumper", "left_bumper") ] elif msg["type"] == "arm_values": - # print(msg["buttons"]) - # d_pad_x = msg["axes"][self.xbox_mappings["d_pad_x"]] # if d_pad_x > 0.5: # ra_slow_mode = True @@ -379,16 +376,10 @@ def handle_controls_message(self, msg): self.filter_xbox_axis(msg["axes"][self.ra_config["joint_a"]["xbox_index"]]), self.filter_xbox_axis(msg["axes"][self.ra_config["joint_b"]["xbox_index"]]), self.filter_xbox_axis(msg["axes"][self.ra_config["joint_c"]["xbox_index"]]), - self.filter_xbox_axis( - msg["axes"][self.ra_config["joint_de_pitch"]["xbox_index_right"]] - - msg["axes"][self.ra_config["joint_de_pitch"]["xbox_index_left"]] - ), - self.filter_xbox_axis( - msg["buttons"][self.ra_config["joint_de_roll"]["xbox_index_right"]] - - msg["buttons"][self.ra_config["joint_de_roll"]["xbox_index_left"]] - ), + self.filter_xbox_button(msg["buttons"], "right_trigger", "left_trigger"), + self.filter_xbox_button(msg["buttons"], "left_bumper", "right_bumper"), self.ra_config["allen_key"]["multiplier"] * self.filter_xbox_button(msg["buttons"], "y", "a"), - self.ra_config["gripper"]["multiplier"] * self.filter_xbox_button(msg["buttons"], "b", "x"), + self.ra_config["gripper"]["multiplier"] * self.filter_xbox_button(msg["buttons"], "x", "b"), ] for i, name in enumerate(self.RA_NAMES): @@ -409,8 +400,8 @@ def handle_controls_message(self, msg): fast_mode_activated = msg["buttons"][self.xbox_mappings["a"]] or msg["buttons"][self.xbox_mappings["b"]] if not fast_mode_activated: for i, name in enumerate(SA_NAMES): - # When going up (vel > 0) with SA joint 2, we DON'T want slow mode. - if not (name == "sa_y" and throttle_cmd.throttles[i] > 0): + # When going up (vel < 0) with SA joint 2, we DON'T want slow mode. + if not (name == "sa_z" and throttle_cmd.throttles[i] < 0): throttle_cmd.throttles[i] *= self.sa_config[name]["slow_mode_multiplier"] publishers[2].publish(throttle_cmd) diff --git a/src/teleoperation/frontend/src/components/ArmControls.vue b/src/teleoperation/frontend/src/components/ArmControls.vue index f086e00fd..5a0bf132f 100644 --- a/src/teleoperation/frontend/src/components/ArmControls.vue +++ b/src/teleoperation/frontend/src/components/ArmControls.vue @@ -98,7 +98,7 @@ import MotorAdjust from './MotorAdjust.vue' import LimitSwitch from './LimitSwitch.vue' // In seconds -const updateRate = 0.01 +const updateRate = 0.05 let interval: number | undefined export default defineComponent({ diff --git a/src/teleoperation/frontend/src/components/CameraFeed.vue b/src/teleoperation/frontend/src/components/CameraFeed.vue index 4f983c60e..efbce30af 100644 --- a/src/teleoperation/frontend/src/components/CameraFeed.vue +++ b/src/teleoperation/frontend/src/components/CameraFeed.vue @@ -64,14 +64,14 @@ export default defineComponent({ mounted: function () { this.startStream(this.id) - this.$nextTick(() => { - const canvas: HTMLCanvasElement = document.getElementById( - 'stream-' + this.id - ) as HTMLCanvasElement - const context = canvas.getContext('2d') ?? new CanvasRenderingContext2D() - context.fillStyle = 'black' - context.fillRect(0, 0, canvas.width, canvas.height) - }) + // this.$nextTick(() => { + // const canvas: HTMLCanvasElement = document.getElementById( + // 'stream-' + this.id + // ) as HTMLCanvasElement + // const context = canvas.getContext('2d') ?? new CanvasRenderingContext2D() + // context.fillStyle = 'black' + // context.fillRect(0, 0, canvas.width, canvas.height) + // }) }, methods: { diff --git a/src/teleoperation/frontend/src/components/Chlorophyll.vue b/src/teleoperation/frontend/src/components/Chlorophyll.vue index 03ff55f4c..2a47d632d 100644 --- a/src/teleoperation/frontend/src/components/Chlorophyll.vue +++ b/src/teleoperation/frontend/src/components/Chlorophyll.vue @@ -49,7 +49,7 @@