]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
clean repo
authorFederica Di Lauro <federicadilauro1998@gmail.com>
Mon, 27 Jan 2020 16:39:06 +0000 (17:39 +0100)
committerFederica Di Lauro <federicadilauro1998@gmail.com>
Mon, 27 Jan 2020 16:39:06 +0000 (17:39 +0100)
20 files changed:
.gitignore
otto_controller/otto_controller_source Debug.cfg [deleted file]
otto_controller/otto_controller_source Debug.launch [deleted file]
utils/catkin_ws/README.md [new file with mode: 0644]
utils/catkin_ws/joypad.launch [moved from utils/catkin_ws/test.launch with 63% similarity]
utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py [new file with mode: 0755]
utils/catkin_ws/src/joypad_bridge/scripts/joy_to_cmd_vel.py
utils/catkin_ws/src/joypad_bridge/scripts/listener.py [deleted file]
utils/pid_tuning/README.md [moved from utils/pid_tuning/pid_tuning_README.md with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/data/left-motor-2019-12-18-11-55-33.csv [moved from utils/pid_tuning/pid_test_matlab/data/left-motor-2019-12-18-11-55-33.csv with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/data/right-motor-2019-12-18-11-24-51.csv [moved from utils/pid_tuning/pid_test_matlab/data/right-motor-2019-12-18-11-24-51.csv with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/matlab_pid_test.mat [moved from utils/pid_tuning/pid_test_matlab/matlab_pid_test.mat with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/pid_logger.py [moved from utils/pid_tuning/pid_test_matlab/pid_logger.py with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/test2_matlab_left.png [moved from utils/pid_tuning/pid_test_matlab/test2_matlab_left.png with 100% similarity]
utils/pid_tuning/old_pid_test_matlab/test_matlab_pid_left.png [moved from utils/pid_tuning/pid_test_matlab/test_matlab_pid_left.png with 100% similarity]
utils/pid_tuning/receive.py [deleted file]
utils/py_serial_examples/receive.py [moved from utils/python_serial_examples/receive.py with 100% similarity]
utils/py_serial_examples/transmit.py [moved from utils/python_serial_examples/transmit.py with 100% similarity]
utils/ticks_calibration/README.md [new file with mode: 0644]
utils/ticks_calibration/receive.py [deleted file]

index 15ec1e4d4a2c88c7bbfe4d4eed579a357d816b33..66b9ca5dd131e0d533f12b753cf6b4d0ad3ad04d 100644 (file)
@@ -54,3 +54,5 @@ dkms.conf
 # Eclipse
 .metadata/
 RemoteSystemsTempFiles/
+*/Debug
+*/Release
diff --git a/otto_controller/otto_controller_source Debug.cfg b/otto_controller/otto_controller_source Debug.cfg
deleted file mode 100644 (file)
index 12d525f..0000000
+++ /dev/null
@@ -1,40 +0,0 @@
-# This is an genericBoard board with a single STM32F767ZITx chip
-#
-# Generated by STM32CubeIDE
-# Take care that such file, as generated, may be overridden without any early notice. Please have a look to debug launch configuration setup(s)
-
-source [find interface/stlink.cfg]
-
-set WORKAREASIZE 0x8000
-
-transport select "hla_swd"
-
-set CHIPNAME STM32F767ZITx
-set BOARDNAME genericBoard
-
-# Enable debug when in low power modes
-set ENABLE_LOW_POWER 1
-
-# Stop Watchdog counters when halt
-set STOP_WATCHDOG 1
-
-# STlink Debug clock frequency
-set CLOCK_FREQ 8000
-
-# Reset configuration
-# use hardware reset, connect under reset
-# connect_assert_srst needed if low power mode application running (WFI...)
-reset_config srst_only srst_nogate connect_assert_srst
-set CONNECT_UNDER_RESET 1
-set CORE_RESET 0
-
-
-
-# BCTM CPU variables
-
-
-
-source [find target/stm32f7x.cfg]
-
-
diff --git a/otto_controller/otto_controller_source Debug.launch b/otto_controller/otto_controller_source Debug.launch
deleted file mode 100644 (file)
index 4430a2d..0000000
+++ /dev/null
@@ -1,96 +0,0 @@
-<?xml version="1.0" encoding="UTF-8" standalone="no"?>
-<launchConfiguration type="com.st.stm32cube.ide.mcu.debug.launch.launchConfigurationType">
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.device" value="STM32F767ZI"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.endian" value="little"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.init_speed" value="4000"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.jlink_check_serial_number" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.jlink_script_path" value=""/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.jlink_script_used" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.jlink_txt_serial_number" value=""/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.reset_strategy" value="type_0_normal"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.scan_chain_auto" value="true"/>
-<intAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.scan_chain_irpre" value="0"/>
-<intAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.scan_chain_pos" value="0"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.jlink.selected_rtos" value="No RTOS"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.access_port_id" value="0"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_live_expr" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_swv" value="true"/>
-<intAttribute key="com.st.stm32cube.ide.mcu.debug.launch.formatVersion" value="2"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.ip_address_local" value="localhost"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.loadList" value="{&quot;fItems&quot;:[{&quot;fIsFromMainTab&quot;:true,&quot;fPath&quot;:&quot;Debug/otto_controller_source.elf&quot;,&quot;fProjectName&quot;:&quot;otto_controller_source&quot;,&quot;fPerformBuild&quot;:true,&quot;fDownload&quot;:true,&quot;fLoadSymbols&quot;:true}]}"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.remoteCommand" value="target remote"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startServer" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.divby0" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.unaligned" value="false"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.haltonexception" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swd_mode" value="true"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_port" value="61235"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_div" value="8"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_hclk" value="16000000"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_wait_for_sync" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.useRemoteTarget" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.verify_flash_download" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_DEVICE_SHAREABLE_ALLOWED" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_INTERFACE" value="Swd"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_INTERFACE_FREQUENCY" value="8000000.0"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_LOW_POWER_MODE_ALLOWED" value="true"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_RESET_MODE" value="connect_under_reset"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.DBG_STOP_WATCHDOG_THEN_HALTED_ALLOWED" value="true"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.OPENOCD_GENERATOR_OPTION" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.OPENOCD_NAME" value="&quot;${stm32cubeide_openocd_path}/openocd&quot;"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.OPENOCD_OTHER_OPTIONS" value=""/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.OPENOCD_SCRIPT" value="${ProjDirPath}/otto_controller_source Debug.cfg"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.openocd.OPENOCD_SCRIPT_CHOICE" value="automated"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_allow_halt" value="false"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_signal_halt" value="false"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_external_loader" value="false"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_logging" value="false"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_shared_stlink" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.external_loader" value=""/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.halt_all_on_reset" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.log_file" value="/home/fdila/Projects/otto/otto_controller_source/Debug/st-link_gdbserver_log.txt"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.reset_strategy" value="system_reset"/>
-<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_check_serial_number" value="false"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_txt_serial_number" value=""/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.datatrace_0" value="Enabled=true:Address=0x20000344:Access=Read/Write:Size=Byte:Function=Data Value + PC"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.datatrace_1" value="Enabled=true:Address=left_velocity:Access=Read/Write:Size=Word:Function=Data Value"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.datatrace_2" value="Enabled=false:Address=0x0:Access=Read/Write:Size=Word:Function=Data Value"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.datatrace_3" value="Enabled=false:Address=0x0:Access=Read/Write:Size=Word:Function=Data Value"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.itmports" value="1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1:1"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.itmports_priv" value="1:1:1:1"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.pc_sample" value="1:128"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.timestamps" value="1:1"/>
-<stringAttribute key="com.st.stm32cube.ide.mcu.debug.swv.trace_events" value="Cpi=1:Exc=0:Sleep=0:Lsu=0:Fold=0:Exetrc=0"/>
-<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doHalt" value="false"/>
-<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doReset" value="false"/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.initCommands" value=""/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.ipAddress" value="localhost"/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.jtagDevice" value="ST-LINK (ST-LINK GDB server)"/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.pcRegister" value=""/>
-<intAttribute key="org.eclipse.cdt.debug.gdbjtag.core.portNumber" value="61234"/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.runCommands" value=""/>
-<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setPcRegister" value="false"/>
-<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setResume" value="true"/>
-<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setStopAt" value="true"/>
-<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.stopAt" value="main"/>
-<stringAttribute key="org.eclipse.cdt.dsf.gdb.DEBUG_NAME" value="${TOOLCHAIN_PATH}/arm-none-eabi-gdb"/>
-<booleanAttribute key="org.eclipse.cdt.dsf.gdb.NON_STOP" value="true"/>
-<booleanAttribute key="org.eclipse.cdt.dsf.gdb.UPDATE_THREADLIST_ON_SUSPEND" value="false"/>
-<intAttribute key="org.eclipse.cdt.launch.ATTR_BUILD_BEFORE_LAUNCH_ATTR" value="2"/>
-<stringAttribute key="org.eclipse.cdt.launch.COREFILE_PATH" value=""/>
-<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_START_MODE" value="remote"/>
-<booleanAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN" value="true"/>
-<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN_SYMBOL" value="main"/>
-<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="Debug/otto_controller_source.elf"/>
-<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="otto_controller_source"/>
-<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="true"/>
-<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.41926027"/>
-<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
-<listEntry value="/otto_controller_source"/>
-</listAttribute>
-<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
-<listEntry value="4"/>
-</listAttribute>
-<stringAttribute key="org.eclipse.dsf.launch.MEMORY_BLOCKS" value="&lt;?xml version=&quot;1.0&quot; encoding=&quot;UTF-8&quot; standalone=&quot;no&quot;?&gt;&#10;&lt;memoryBlockExpressionList context=&quot;reserved-for-future-use&quot;&gt;&#10;&lt;gdbmemoryBlockExpression address=&quot;0&quot; label=&quot;left_velocity&quot;/&gt;&#10;&lt;/memoryBlockExpressionList&gt;&#10;"/>
-<stringAttribute key="process_factory_id" value="org.eclipse.cdt.dsf.gdb.GdbProcessFactory"/>
-</launchConfiguration>
diff --git a/utils/catkin_ws/README.md b/utils/catkin_ws/README.md
new file mode 100644 (file)
index 0000000..1dd7c9f
--- /dev/null
@@ -0,0 +1,11 @@
+### ROS workspace
+
+This workspace contains useful ros nodes to drive Otto and get the odometry.
+
+ROS nodes:
+
+*joy_to_cmd_vel: used to translate joy msgs to cmd_vel msgs
+*cmd_vel_transmitter: used to send the velocities setpoints to the board through the serial adapter.
+
+ROS launches:
+* joypad.launch: launches the necessary nodes to drive Otto with a joypad. Requires joy, joy_to_cmd_vel, cmd_vel_transmitter.
\ No newline at end of file
similarity index 63%
rename from utils/catkin_ws/test.launch
rename to utils/catkin_ws/joypad.launch
index ed8edaf09c4b7fbd0c0486ba5c972d169c1fe467..69f8ec651ed8719c3ee96a9e44a87fb05eb87ff6 100644 (file)
@@ -1,6 +1,5 @@
 <launch>
   <node name="joy_node" pkg="joy" type="joy_node" />
   <node name="joy_to_cmd_vel" pkg="joypad_bridge" type="joy_to_cmd_vel.py"/>
-  <node name="listener" pkg="joypad_bridge" type="listener.py"/>
-  
+  <node name="cmd_vel_transmitter" pkg="joypad_bridge" type="cmd_vel_transmitter.py"/>
 </launch>
diff --git a/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py b/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py
new file mode 100755 (executable)
index 0000000..ae2859c
--- /dev/null
@@ -0,0 +1,42 @@
+#!/usr/bin/env python
+
+import rospy, serial, struct, time
+from geometry_msgs.msg import Twist
+
+ser = serial.Serial(
+       port='/dev/ttyUSB0',
+        baudrate=115200,
+        parity=serial.PARITY_NONE,
+        stopbits=serial.STOPBITS_ONE,
+        bytesize=serial.EIGHTBITS,
+        rtscts=False)
+
+current_millis = 0 
+last_millis = 0
+
+def callback(data):
+    global current_millis
+    global last_millis
+    #da fixare
+    linear = -data.linear.x
+    angular = -data.angular.z
+    last_millis = current_millis
+    current_millis = int(round(time.time() * 1000))
+    rospy.loginfo('I heard %f %f', linear, angular)
+    if (1):
+        msg_output = struct.pack('<ff', linear, angular)
+        ser.write(msg_output)
+        ser.flush()
+    
+
+
+def listener():
+
+    rospy.init_node('cmd_vel_transmitter', anonymous=True)
+
+    rospy.Subscriber('/cmd_vel', Twist, callback)
+
+    rospy.spin()
+
+if __name__ == '__main__':
+    listener()
index ea518a4546f96466e6974c62123ca36d5a60c536..9c8f166b908451b614d2f6be4cc37c905b8fdc12 100755 (executable)
@@ -3,29 +3,17 @@ import rospy
 from geometry_msgs.msg import Twist
 from sensor_msgs.msg import Joy
 
-# Author: Andrew Dai
-# This ROS Node converts Joystick inputs from the joy node
-# into cmd_vel
-
-# Receives joystick messages (subscribed to Joy topic)
-# then converts the joysick inputs into Twist commands
-# axis 1 aka left stick vertical controls linear speed
-# axis 0 aka left stick horizonal controls angular speed
 def callback(data):
     twist = Twist()
     twist.linear.x = data.axes[2]
     twist.angular.z = data.axes[0]
     pub.publish(twist)
 
-#Intializes everything
 def start():
-    # publishing to "turtle1/cmd_vel" to control turtle1
     global pub
     rospy.init_node('joy_to_cmd_vel')
     pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
-    # subscribed to joystick inputs on topic "joy"
     rospy.Subscriber("joy", Joy, callback)
-    # starts the node
     rospy.spin()
 
 if __name__ == '__main__':
diff --git a/utils/catkin_ws/src/joypad_bridge/scripts/listener.py b/utils/catkin_ws/src/joypad_bridge/scripts/listener.py
deleted file mode 100755 (executable)
index 66acc48..0000000
+++ /dev/null
@@ -1,84 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-#  * Redistributions of source code must retain the above copyright
-#    notice, this list of conditions and the following disclaimer.
-#  * Redistributions in binary form must reproduce the above
-#    copyright notice, this list of conditions and the following
-#    disclaimer in the documentation and/or other materials provided
-#    with the distribution.
-#  * Neither the name of Willow Garage, Inc. nor the names of its
-#    contributors may be used to endorse or promote products derived
-#    from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-# Revision $Id$
-
-## Simple talker demo that listens to std_msgs/Strings published 
-## to the 'chatter' topic
-
-import rospy, serial, struct, time
-from geometry_msgs.msg import Twist
-
-ser = serial.Serial(
-       port='/dev/ttyUSB0',
-        baudrate=115200,
-        parity=serial.PARITY_NONE,
-        stopbits=serial.STOPBITS_ONE,
-        bytesize=serial.EIGHTBITS,
-        rtscts=False)
-
-current_millis = 0 
-last_millis = 0
-
-def callback(data):
-    global current_millis
-    global last_millis
-    #da fixare
-    linear = -data.linear.x
-    angular = -data.angular.z
-    last_millis = current_millis
-    current_millis = int(round(time.time() * 1000))
-    rospy.loginfo('I heard %f %f', linear, angular)
-    if (1):
-        msg_output = struct.pack('<ff', linear, angular)
-        ser.write(msg_output)
-        ser.flush()
-    
-
-
-def listener():
-
-    # In ROS, nodes are uniquely named. If two nodes with the same
-    # name are launched, the previous one is kicked off. The
-    # anonymous=True flag means that rospy will choose a unique
-    # name for our 'listener' node so that multiple listeners can
-    # run simultaneously.
-    rospy.init_node('listener', anonymous=True)
-
-    rospy.Subscriber('/cmd_vel', Twist, callback)
-
-    # spin() simply keeps python from exiting until this node is stopped
-    rospy.spin()
-
-if __name__ == '__main__':
-    listener()
diff --git a/utils/pid_tuning/receive.py b/utils/pid_tuning/receive.py
deleted file mode 100644 (file)
index c2a1261..0000000
+++ /dev/null
@@ -1,16 +0,0 @@
-import serial, struct, time
-ser = serial.Serial(
-       port='/dev/ttyUSB0',
-        baudrate=115200,
-        parity=serial.PARITY_ODD,
-        stopbits=serial.STOPBITS_ONE,
-        bytesize=serial.EIGHTBITS,
-        rtscts=False)
-
-while 1:
-       ser.reset_input_buffer()
-       buffer = ser.read(8)
-       msg_received = struct.unpack('<fi', buffer)
-       print(msg_received)
-       print(buffer)   
-
diff --git a/utils/ticks_calibration/README.md b/utils/ticks_calibration/README.md
new file mode 100644 (file)
index 0000000..0f40e38
--- /dev/null
@@ -0,0 +1,5 @@
+### Ticks calibration
+
+* Flash otto_\ticks\_calibration on the board
+* Run ticks_logger.py
+* Run the required ros nodes to drive otto with a joypad
\ No newline at end of file
diff --git a/utils/ticks_calibration/receive.py b/utils/ticks_calibration/receive.py
deleted file mode 100644 (file)
index e7637d7..0000000
+++ /dev/null
@@ -1,16 +0,0 @@
-import serial, struct, time
-ser = serial.Serial(
-       port='/dev/ttyUSB0',
-        baudrate=115200,
-        parity=serial.PARITY_NONE,
-        stopbits=serial.STOPBITS_ONE,
-        bytesize=serial.EIGHTBITS,
-        rtscts=False)
-
-while 1:
-       ser.reset_input_buffer()
-       buffer = ser.read(8)
-       msg_received = struct.unpack('<ii', buffer)
-       print(msg_received)
-       print(buffer)
-