Some new drive code. Firmware too, but that's not up yet.

This commit is contained in:
2018-02-11 21:18:40 -08:00
parent 940d2782c3
commit ad4bf7d74c
6 changed files with 407 additions and 87 deletions

View File

@@ -1,7 +1,25 @@
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyDEV0"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyDEV0"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyDEV1"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyDEV1"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyCompass"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyCompass"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyGPS"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyGPS"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_0_0"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_0_1"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_0_2"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_0_3"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_1_0"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_1_1"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_1_2"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_1_3"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_2_0"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_2_1"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_2_2"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_2_3"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", ATTRS{serial}=="AH05K2Y8", SYMLINK+="rover/ttyTEST"

View File

@@ -13,7 +13,7 @@
<option name="LAST_RESOLUTION" value="IGNORE" />
</component>
<component name="CoverageDataManager">
<SUITE FILE_PATH="coverage/rover_drive$Local_Launch.coverage" NAME="Local Launch Coverage Results" MODIFIED="1517706589165" SOURCE_PROVIDER="com.intellij.coverage.DefaultCoverageFileProvider" RUNNER="coverage.py" COVERAGE_BY_TEST_ENABLED="true" COVERAGE_TRACING_ENABLED="false" WORKING_DIRECTORY="$PROJECT_DIR$/src" />
<SUITE FILE_PATH="coverage/rover_drive$Local_Launch.coverage" NAME="Local Launch Coverage Results" MODIFIED="1518128882987" SOURCE_PROVIDER="com.intellij.coverage.DefaultCoverageFileProvider" RUNNER="coverage.py" COVERAGE_BY_TEST_ENABLED="true" COVERAGE_TRACING_ENABLED="false" WORKING_DIRECTORY="$PROJECT_DIR$/src" />
</component>
<component name="CreatePatchCommitExecutor">
<option name="PATCH_PATH" value="" />
@@ -27,8 +27,8 @@
<file leaf-file-name="test.py" pinned="false" current-in-tab="false">
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="82">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<state relative-caret-position="36">
<caret line="4" column="0" selection-start-line="4" selection-start-column="0" selection-end-line="22" selection-end-column="0" />
<folding />
</state>
</provider>
@@ -37,8 +37,8 @@
<file leaf-file-name="rover_drive_node.py" pinned="false" current-in-tab="false">
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="334">
<caret line="94" column="107" selection-start-line="94" selection-start-column="107" selection-end-line="94" selection-end-column="107" />
<state relative-caret-position="1134">
<caret line="63" column="23" selection-start-line="63" selection-start-column="23" selection-end-line="63" selection-end-column="23" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
@@ -46,11 +46,11 @@
</provider>
</entry>
</file>
<file leaf-file-name="rover_drive_node_tester.py" pinned="false" current-in-tab="true">
<file leaf-file-name="rover_drive_node_tester.py" pinned="false" current-in-tab="false">
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="162">
<caret line="9" column="16" selection-start-line="9" selection-start-column="16" selection-end-line="9" selection-end-column="16" />
<state relative-caret-position="144">
<caret line="13" column="17" selection-start-line="13" selection-start-column="17" selection-end-line="13" selection-end-column="17" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
@@ -58,31 +58,11 @@
</provider>
</entry>
</file>
<file leaf-file-name="package.xml" pinned="false" current-in-tab="false">
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="567">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
</file>
<file leaf-file-name="RoverMotorDrive.msg" pinned="false" current-in-tab="false">
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
<folding />
</state>
</provider>
</entry>
</file>
<file leaf-file-name="example.launch" pinned="false" current-in-tab="false">
<file leaf-file-name="example.launch" pinned="false" current-in-tab="true">
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<state relative-caret-position="54">
<caret line="3" column="54" selection-start-line="3" selection-start-column="54" selection-end-line="3" selection-end-column="54" />
<folding />
</state>
</provider>
@@ -104,9 +84,10 @@
<option value="$PROJECT_DIR$/CMakeLists.txt" />
<option value="$PROJECT_DIR$/src/rover_drive.py" />
<option value="$PROJECT_DIR$/package.xml" />
<option value="$PROJECT_DIR$/launch/example.launch" />
<option value="$PROJECT_DIR$/src/rover_drive_node.py" />
<option value="$PROJECT_DIR$/src/rover_drive_node_tester.py" />
<option value="$USER_HOME$/PycharmProjects/485_test/test.py" />
<option value="$PROJECT_DIR$/launch/example.launch" />
</list>
</option>
</component>
@@ -118,7 +99,7 @@
</component>
<component name="ProjectFrameBounds">
<option name="x" value="1920" />
<option name="width" value="1680" />
<option name="width" value="1678" />
<option name="height" value="1020" />
</component>
<component name="ProjectLevelVcsManager" settingsEditedManually="false">
@@ -470,16 +451,16 @@
<servers />
</component>
<component name="ToolWindowManager">
<frame x="1920" y="0" width="1680" height="1020" extended-state="6" />
<frame x="1920" y="0" width="1678" height="1020" extended-state="5" />
<editor active="true" />
<layout>
<window_info id="Project" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="true" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="0" side_tool="false" content_ui="combo" />
<window_info id="Project" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="true" show_stripe_button="true" weight="0.18383233" sideWeight="0.5" order="0" side_tool="false" content_ui="combo" />
<window_info id="TODO" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="6" side_tool="false" content_ui="tabs" />
<window_info id="Event Log" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="7" side_tool="true" content_ui="tabs" />
<window_info id="Database" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="3" side_tool="false" content_ui="tabs" />
<window_info id="Version Control" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="7" side_tool="false" content_ui="tabs" />
<window_info id="Python Console" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.32897604" sideWeight="0.5" order="7" side_tool="false" content_ui="tabs" />
<window_info id="Run" active="true" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="true" show_stripe_button="true" weight="0.32897604" sideWeight="0.5" order="2" side_tool="false" content_ui="tabs" />
<window_info id="Run" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="true" show_stripe_button="true" weight="0.3278867" sideWeight="0.5" order="2" side_tool="false" content_ui="tabs" />
<window_info id="Structure" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="1" side_tool="false" content_ui="tabs" />
<window_info id="Terminal" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="7" side_tool="false" content_ui="tabs" />
<window_info id="Favorites" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="2" side_tool="true" content_ui="tabs" />
@@ -509,6 +490,246 @@
<watches-manager />
</component>
<component name="editorHistoryManager">
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
<caret line="0" column="0" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1134">
<caret line="63" column="23" selection-start-line="63" selection-start-column="23" selection-end-line="63" selection-end-column="23" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="13" column="17" selection-start-line="13" selection-start-column="17" selection-end-line="13" selection-end-column="17" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="252">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1746">
<caret line="97" column="45" selection-start-line="97" selection-start-column="45" selection-end-line="97" selection-end-column="45" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
<caret line="0" column="0" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1044">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="288">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1602">
<caret line="94" column="107" selection-start-line="94" selection-start-column="107" selection-end-line="94" selection-end-column="107" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
<caret line="0" column="0" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1044">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="252">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1602">
<caret line="94" column="107" selection-start-line="94" selection-start-column="107" selection-end-line="94" selection-end-column="107" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
<caret line="0" column="0" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1044">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="252">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1602">
<caret line="94" column="107" selection-start-line="94" selection-start-column="107" selection-end-line="94" selection-end-column="107" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
<caret line="0" column="0" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1044">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="0">
@@ -523,7 +744,6 @@
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
<folding />
</state>
</provider>
</entry>
@@ -542,34 +762,35 @@
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/package.xml">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="567">
<state relative-caret-position="524">
<caret line="58" column="0" selection-start-line="58" selection-start-column="0" selection-end-line="58" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="144">
<caret line="8" column="0" selection-start-line="8" selection-start-column="0" selection-end-line="8" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/msg/RoverMotorDrive.msg">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="108">
<caret line="6" column="25" selection-start-line="6" selection-start-column="25" selection-end-line="6" selection-end-column="25" />
<folding />
<caret line="13" column="17" selection-start-line="13" selection-start-column="17" selection-end-line="13" selection-end-column="17" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="334">
<caret line="94" column="107" selection-start-line="94" selection-start-column="107" selection-end-line="94" selection-end-column="107" />
<state relative-caret-position="1134">
<caret line="63" column="23" selection-start-line="63" selection-start-column="23" selection-end-line="63" selection-end-column="23" />
<folding>
<element signature="e#132#151#0" expanded="true" />
</folding>
@@ -578,19 +799,17 @@
</entry>
<entry file="file://$USER_HOME$/PycharmProjects/485_test/test.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="82">
<caret line="16" column="0" selection-start-line="16" selection-start-column="0" selection-end-line="18" selection-end-column="12" />
<state relative-caret-position="36">
<caret line="4" column="0" selection-start-line="4" selection-start-column="0" selection-end-line="22" selection-end-column="0" />
<folding />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/src/rover_drive_node_tester.py">
<entry file="file://$PROJECT_DIR$/launch/example.launch">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="162">
<caret line="9" column="16" selection-start-line="9" selection-start-column="16" selection-end-line="9" selection-end-column="16" />
<folding>
<element signature="e#0#12#0" expanded="true" />
</folding>
<state relative-caret-position="54">
<caret line="3" column="54" selection-start-line="3" selection-start-column="54" selection-end-line="3" selection-end-column="54" />
<folding />
</state>
</provider>
</entry>

View File

@@ -1,8 +1,8 @@
<launch>
<group ns="drive">
<node name="" pkg="rover_drive" type="rover_drive_node.py" launch-prefix="taskset -c 5" output="screen">
<param name="port" value="/dev/ttyUSB0"/>
<param name="baud" value="2000000"/>
<param name="port" value="/dev/rover/ttyIRIS_1_0"/>
<param name="baud" value="2000000"/>
</node>
</group>
</launch>

View File

@@ -0,0 +1,60 @@
import rospy
import time
import atexit
import signal
import serial.rs485
import minimalmodbus
from rover_drive.msg import RoverMotorDrive
signal.signal(signal.SIGINT, signal.SIG_DFL)
rospy.init_node("drive_tester")
pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=1)
def make_instr(port_name, baud):
instr = minimalmodbus.Instrument(port_name, 1)
instr.serial = serial.rs485.RS485(port_name, baudrate=baud, timeout=0.05)
instr.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0, delay_before_rx=0,
delay_before_tx=0)
return instr
sbus = make_instr("/dev/rover/ttyIRIS_2_2", 2000000)
max = 1811
mid = 990
min = 172
scalar = 75
drive = RoverMotorDrive()
while not rospy.is_shutdown():
left, right = sbus.read_registers(0, 2)
# print left
drive.first_motor_direction = 1 if left > mid else 0
drive.first_motor_speed = abs(left - mid ) * scalar
# print drive.first_motor_speed
pub.publish(drive)
# try:
# drive = RoverMotorDrive()
#
# last_dir = not last_dir
# for i in range(0, 65535, speed_step):
# drive.first_motor_direction = last_dir
# drive.first_motor_speed = i
# pub.publish(drive)
# time.sleep(sleep_time)
# print i
# for i in range(65535, 0, -speed_step):
# drive.first_motor_direction = last_dir
# drive.first_motor_speed = i
# pub.publish(drive)
# time.sleep(sleep_time)
# print i
# except KeyboardInterrupt:
# exit()

View File

@@ -61,6 +61,7 @@ class RoverDrive(object):
self.first_motor = minimalmodbus.Instrument(self.port, self.first_motor_modbus_id)
self.second_motor = minimalmodbus.Instrument(self.port, self.second_motor_modbus_id)
print self.port
self.motors_subscriber = rospy.Subscriber(MOTOR_TOPIC, RoverMotorDrive, self.__motor_message_callback)
@@ -91,11 +92,14 @@ class RoverDrive(object):
serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0, delay_before_rx=0, delay_before_tx=0)
def __motor_message_callback(self, data):
first_motor_register_data = list(MOTOR_DRIVER_DEFAULT_MESSAGE) # Makes a copy
first_motor_register_data[MOTOR_DRIVER_REGISTER_MAP["DIRECTION"]] = int(data.first_motor_direction)
first_motor_register_data[MOTOR_DRIVER_REGISTER_MAP["SPEED"]] = data.first_motor_speed
print first_motor_register_data
self.first_motor.write_registers(0, first_motor_register_data)
try:
first_motor_register_data = list(MOTOR_DRIVER_DEFAULT_MESSAGE) # Makes a copy
first_motor_register_data[MOTOR_DRIVER_REGISTER_MAP["DIRECTION"]] = int(data.first_motor_direction)
first_motor_register_data[MOTOR_DRIVER_REGISTER_MAP["SPEED"]] = data.first_motor_speed
# print first_motor_register_data
self.first_motor.write_registers(0, first_motor_register_data)
except:
print "Drive exception"
#####################################
# Main Definition

View File

@@ -1,31 +1,50 @@
import rospy
import time
import atexit
import signal
from rover_drive.msg import RoverMotorDrive
signal.signal(signal.SIGINT, signal.SIG_DFL)
rospy.init_node("drive_tester")
pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=10)
pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=1)
speed_step = 500
speed_step = 1000
last_dir = 0
sleep_time = 0.01
sleep_time = 0.1
def stop_motors():
global pub
drive.first_motor_direction = last_dir
drive.first_motor_speed = 0
pub.publish(drive)
atexit.register(stop_motors)
while not rospy.is_shutdown():
drive = RoverMotorDrive()
try :
drive = RoverMotorDrive()
last_dir = not last_dir
for i in range(0, 65535, speed_step):
drive.first_motor_direction = last_dir
drive.first_motor_speed = i
pub.publish(drive)
time.sleep(sleep_time)
print i
for i in range(65535, 0, -speed_step):
drive.first_motor_direction = last_dir
drive.first_motor_speed = i
pub.publish(drive)
time.sleep(sleep_time)
print i
except KeyboardInterrupt:
exit()
last_dir = not last_dir
for i in range(0, 65535, speed_step):
drive.first_motor_direction = last_dir
drive.first_motor_speed = i
pub.publish(drive)
time.sleep(sleep_time)
print i
for i in range(65535, 0, -speed_step):
drive.first_motor_direction = last_dir
drive.first_motor_speed = i
pub.publish(drive)
time.sleep(sleep_time)
print i