From 6b381217c7a1b76de385236152339b27f5bc0f62 Mon Sep 17 00:00:00 2001 From: MisterMap Date: Sun, 4 Nov 2018 15:37:09 +0300 Subject: [PATCH 01/40] Create .gitignore --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..11cc596 --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +*.pyc +*.idea +*.swp From f5bbce398e6a6422e67ce11fbc34f0d43cb30889 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Mon, 19 Nov 2018 18:52:15 +0300 Subject: [PATCH 02/40] create stm_node --- eurobot_stm/CMakeLists.txt | 199 ++++++++++++++++++++++++++++ eurobot_stm/package.xml | 68 ++++++++++ eurobot_stm/scripts/STM_node.py | 65 +++++++++ eurobot_stm/scripts/STM_protocol.py | 119 +++++++++++++++++ 4 files changed, 451 insertions(+) create mode 100644 eurobot_stm/CMakeLists.txt create mode 100644 eurobot_stm/package.xml create mode 100755 eurobot_stm/scripts/STM_node.py create mode 100755 eurobot_stm/scripts/STM_protocol.py diff --git a/eurobot_stm/CMakeLists.txt b/eurobot_stm/CMakeLists.txt new file mode 100644 index 0000000..efcd9ac --- /dev/null +++ b/eurobot_stm/CMakeLists.txt @@ -0,0 +1,199 @@ +cmake_minimum_required(VERSION 2.8.3) +project(eurobot_stm) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES eurobot_stm +# CATKIN_DEPENDS roscpp rospy std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/eurobot_stm.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/eurobot_stm_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_eurobot_stm.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/eurobot_stm/package.xml b/eurobot_stm/package.xml new file mode 100644 index 0000000..69922ee --- /dev/null +++ b/eurobot_stm/package.xml @@ -0,0 +1,68 @@ + + + eurobot_stm + 0.0.0 + The eurobot_stm package + + + + + alexey + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + rospy + std_msgs + roscpp + rospy + std_msgs + roscpp + rospy + std_msgs + + + + + + + + diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py new file mode 100755 index 0000000..433b23e --- /dev/null +++ b/eurobot_stm/scripts/STM_node.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python +import rospy +from std_msgs.msg import String +from threading import Lock +from geometry_msgs.msg import Twist, TransformStamped +from std_msgs.msg import Int32MultiArray +import numpy as np +import time +import struct +import serial +from STM_protocol import STMprotocol + +class STMnode(STMprotocol): + def __init__(self, serial_port, baudrate=115200): + # Init ROS + rospy.init_node('stm_command_node', anonymous=True) + # ROS subscribers + rospy.Subscriber("stm_command", String, self.stm_command_callback) + + super(STMnode, self).__init__(serial_port, baudrate) + self.mutex = Lock() + + def stm_command_callback(self, data): + cmd, args = self.parse_data(data) + successfully = self.send(cmd, args) + + def parse_data(self, data): + data_splitted = data.data.split() + cmd = int(data_splitted[0]) + args = [float(num) for num in data_splitted[1:]] + return cmd, args + + def send(self, cmd, args): + self.mutex.acquire() + successfully, values = self.send_command(cmd, args) + self.mutex.release() + rospy.loginfo('Got response args: ' + str(values)) + return successfully + + def square_test(self): + self.pure_send_command(8, (0.2,0,0)) + time.sleep(3) + self.pure_send_command(8, (0,0.2,0)) + time.sleep(3) + self.pure_send_command(8, (-0.2,0,0)) + time.sleep(3) + self.pure_send_command(8, (0,-0.2,0)) + time.sleep(3) + self.pure_send_command(8, (0,0,0)) + + def triangle(self): + #self.pure_send_command(8, (0,0,3.14)) + #time.sleep(1) + self.pure_send_command(8, (0,0.8,0)) + time.sleep(3) + self.pure_send_command(8, (0.8,0,0)) + time.sleep(3) + self.pure_send_command(8,(-0.8,-0.8,0)) + time.sleep(3) + self.pure_send_command(8, (0,0,0)) + +if __name__ == '__main__': + serial_port = "/dev/ttyUSB0" + stm = STMnode(serial_port) + rospy.spin() diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py new file mode 100755 index 0000000..a318129 --- /dev/null +++ b/eurobot_stm/scripts/STM_protocol.py @@ -0,0 +1,119 @@ +#/usr/bin/env python + +import rospy +import serial +import struct +import time +import datetime + +class STMprotocol(object): + def __init__(self,serial_port, baudrate=115200): + self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) + self.pack_format = { + 0x01: "=BBBB", + 0x03: "=Bf", + 0x04: "=B", + 0x05: "=B", + 0x06: "=Bffff", + 0x08: "=fff", + 0x09: "=", + 0x0a: "=", + 0x0b: "=BH", + 0x0c: "=B", + 0x0d: "=B", + 0xa0: "=", + 0xa1: "=B", + 0xb0: "=B", + 0xb1: "=B", + 0xb2: "=BB", + 0xb3: "=B", + 0xb4: "=B", + 0xb5: "=B", + 0xb6: "=B", + 0x0e: "=fff", + 0x0f: "=", + 0xa2: "=ffffff", + 0xc0: "=", + 0xc1: "=B", + 0xc2: "=B", + 0xc3: "=B", + 0xc4: "=BB", + 0xd0: "=", + 0xd1: "=", + 0xa3: "=", + 0xe0: "=B", + 256: "=H", + 0xa4: "", + 0xb7: "=B" + } + + self.unpack_format = { + 0x01: "=BBBB", + 0x03: "=BB", + 0x04: "=BB", + 0x05: "=BB", + 0x06: "=BB", + 0x08: "cc", + 0x09: "=fff", + 0x0a: "=fff", + 0x0b: "=BB", + 0x0c: "=f", + 0x0d: "=BB", + 0xa0: "=B", + 0xa1: "=B", + 0xb0: "=BB", + 0xb1: "=BB", + 0xb2: "=BB", + 0xb3: "=BB", + 0xb4: "=BB", + 0xb5: "=BB", + 0xb6: "=BB", + 0x0e: "=BB", + 0x0f: "=fff", + 0xa2: "=BB", + 0xc0: "=B", + 0xc1: "=BB", + 0xc2: "=BB", + 0xc3: "=BB", + 0xc4: "=BB", + 0xd0: "=BBBBBBBBBBBBBBBBBBBBBBBBBBBBBBBB", + 0xd1: "=" + "B" * 16, + # 0xd0: "=BBBBBB", + 0xa3: "=B", + 0xe0: "=BB", + 0xa4: "=BB", + 0xb7: "=BB" + } + + def pure_send_command(self, cmd, args): + # Clear buffer + self.ser.reset_output_buffer() + self.ser.reset_input_buffer() + # Sending command + parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) + print ('cmd=', cmd) + msg = bytearray([cmd]) + parameters + print ('msg = ' + str(struct.unpack('=c' + self.pack_format[cmd][1:],msg))) + self.ser.write(msg) + + response = self.ser.readline() + print(response) + if len(response) == 0: + raise Exception("No data received") + values = struct.unpack(self.unpack_format[cmd], response) + + return True, values + + + def send_command(self, cmd, args, n_repeats=5): + # print (cmd, args) + for i in range(n_repeats): + try: + return self.pure_send_command(cmd, args) + except Exception as exc: + if i == n_repeats - 1: + rospy.logerr('Exception:\t %s', str(exc)) + rospy.logerr('At time:\t %s', str(datetime.datetime.now())) + rospy.logerr('cmd: %s args: %s',str(cmd), str(args)) + print('--------------------------') + return False, None From 8d16dc22c77ad31d33e725fd7900ebf545c563fe Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 21 Nov 2018 19:52:24 +0300 Subject: [PATCH 03/40] minor improvements --- eurobot_stm/scripts/STM_node.py | 37 +++--------- eurobot_stm/scripts/STM_protocol.py | 93 +++++------------------------ 2 files changed, 25 insertions(+), 105 deletions(-) diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py index 433b23e..990fb57 100755 --- a/eurobot_stm/scripts/STM_node.py +++ b/eurobot_stm/scripts/STM_node.py @@ -2,22 +2,24 @@ import rospy from std_msgs.msg import String from threading import Lock -from geometry_msgs.msg import Twist, TransformStamped from std_msgs.msg import Int32MultiArray import numpy as np +import datetime import time import struct import serial -from STM_protocol import STMprotocol +import itertools +from STMprotocol import STMprotocol class STMnode(STMprotocol): def __init__(self, serial_port, baudrate=115200): # Init ROS - rospy.init_node('stm_command_node', anonymous=True) + rospy.init_node('stm_node', anonymous=True) # ROS subscribers rospy.Subscriber("stm_command", String, self.stm_command_callback) + rospy.Subscriber("t") - super(STMnode, self).__init__(serial_port, baudrate) + super(STMnode, self).__init__(serial_port, baudrate) self.mutex = Lock() def stm_command_callback(self, data): @@ -27,37 +29,16 @@ def stm_command_callback(self, data): def parse_data(self, data): data_splitted = data.data.split() cmd = int(data_splitted[0]) - args = [float(num) for num in data_splitted[1:]] + args_dict = {'c': int, 'H': int, 'f': float} + args = [action_args_dict[t](s) for t, s in itertools.izip(pack_format[cmd][1:], data_splitted[1:])] return cmd, args def send(self, cmd, args): self.mutex.acquire() successfully, values = self.send_command(cmd, args) self.mutex.release() - rospy.loginfo('Got response args: ' + str(values)) + rospy.loginfo('Got response args: '+ str(values)) return successfully - - def square_test(self): - self.pure_send_command(8, (0.2,0,0)) - time.sleep(3) - self.pure_send_command(8, (0,0.2,0)) - time.sleep(3) - self.pure_send_command(8, (-0.2,0,0)) - time.sleep(3) - self.pure_send_command(8, (0,-0.2,0)) - time.sleep(3) - self.pure_send_command(8, (0,0,0)) - - def triangle(self): - #self.pure_send_command(8, (0,0,3.14)) - #time.sleep(1) - self.pure_send_command(8, (0,0.8,0)) - time.sleep(3) - self.pure_send_command(8, (0.8,0,0)) - time.sleep(3) - self.pure_send_command(8,(-0.8,-0.8,0)) - time.sleep(3) - self.pure_send_command(8, (0,0,0)) if __name__ == '__main__': serial_port = "/dev/ttyUSB0" diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index a318129..479e162 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -1,88 +1,28 @@ -#/usr/bin/env python - -import rospy import serial import struct import time import datetime +import rospy class STMprotocol(object): def __init__(self,serial_port, baudrate=115200): - self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) + self.ser = serial(serial_port,baudrate=baudrate, timeout = 0.01) self.pack_format = { - 0x01: "=BBBB", - 0x03: "=Bf", - 0x04: "=B", - 0x05: "=B", - 0x06: "=Bffff", + 0x01: "=cccc", + 0x07: "=", 0x08: "=fff", 0x09: "=", - 0x0a: "=", - 0x0b: "=BH", - 0x0c: "=B", - 0x0d: "=B", - 0xa0: "=", - 0xa1: "=B", - 0xb0: "=B", - 0xb1: "=B", - 0xb2: "=BB", - 0xb3: "=B", - 0xb4: "=B", - 0xb5: "=B", - 0xb6: "=B", 0x0e: "=fff", 0x0f: "=", - 0xa2: "=ffffff", - 0xc0: "=", - 0xc1: "=B", - 0xc2: "=B", - 0xc3: "=B", - 0xc4: "=BB", - 0xd0: "=", - 0xd1: "=", - 0xa3: "=", - 0xe0: "=B", - 256: "=H", - 0xa4: "", - 0xb7: "=B" } self.unpack_format = { - 0x01: "=BBBB", - 0x03: "=BB", - 0x04: "=BB", - 0x05: "=BB", - 0x06: "=BB", - 0x08: "cc", + 0x01: "=cccc", + 0x07: "=fff", + 0x08: "=cc", 0x09: "=fff", - 0x0a: "=fff", - 0x0b: "=BB", - 0x0c: "=f", - 0x0d: "=BB", - 0xa0: "=B", - 0xa1: "=B", - 0xb0: "=BB", - 0xb1: "=BB", - 0xb2: "=BB", - 0xb3: "=BB", - 0xb4: "=BB", - 0xb5: "=BB", - 0xb6: "=BB", - 0x0e: "=BB", + 0x0e: "=cc", 0x0f: "=fff", - 0xa2: "=BB", - 0xc0: "=B", - 0xc1: "=BB", - 0xc2: "=BB", - 0xc3: "=BB", - 0xc4: "=BB", - 0xd0: "=BBBBBBBBBBBBBBBBBBBBBBBBBBBBBBBB", - 0xd1: "=" + "B" * 16, - # 0xd0: "=BBBBBB", - 0xa3: "=B", - 0xe0: "=BB", - 0xa4: "=BB", - 0xb7: "=BB" } def pure_send_command(self, cmd, args): @@ -93,27 +33,26 @@ def pure_send_command(self, cmd, args): parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) print ('cmd=', cmd) msg = bytearray([cmd]) + parameters - print ('msg = ' + str(struct.unpack('=c' + self.pack_format[cmd][1:],msg))) + print ('msg = ' + str(struct.unpack('=cfff',msg))) self.ser.write(msg) response = self.ser.readline() - print(response) + print(response) if len(response) == 0: raise Exception("No data received") - values = struct.unpack(self.unpack_format[cmd], response) - + + values = struct.unpack(self.unpack_format[cmd], response) return True, values def send_command(self, cmd, args, n_repeats=5): - # print (cmd, args) for i in range(n_repeats): try: return self.pure_send_command(cmd, args) except Exception as exc: if i == n_repeats - 1: - rospy.logerr('Exception:\t %s', str(exc)) - rospy.logerr('At time:\t %s', str(datetime.datetime.now())) - rospy.logerr('cmd: %s args: %s',str(cmd), str(args)) - print('--------------------------') + rospy.logerr('Exception:\t', exc) + rospy.logerr('At time:\t', datetime.datetime.now()) + rospy.logerr('cmd:', cmd, 'args:', args) + rospy.logerr('--------------------------') return False, None From 54a249d2496d376eb80fadacd9791573c33f0f10 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Tue, 11 Dec 2018 20:40:09 +0300 Subject: [PATCH 04/40] some improvements --- eurobot_stm/scripts/STM_node.py | 63 +++++++++++++++++++++++++---- eurobot_stm/scripts/STM_protocol.py | 37 ++++++++++------- 2 files changed, 79 insertions(+), 21 deletions(-) diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py index 990fb57..c8460e4 100755 --- a/eurobot_stm/scripts/STM_node.py +++ b/eurobot_stm/scripts/STM_node.py @@ -3,13 +3,18 @@ from std_msgs.msg import String from threading import Lock from std_msgs.msg import Int32MultiArray +import geometry_msgs.msg +import tf_conversions +import tf2_ros import numpy as np import datetime import time import struct import serial import itertools -from STMprotocol import STMprotocol +from STM_protocol import STMprotocol + +ODOM_RATE = 40 # Hz class STMnode(STMprotocol): def __init__(self, serial_port, baudrate=115200): @@ -17,20 +22,28 @@ def __init__(self, serial_port, baudrate=115200): rospy.init_node('stm_node', anonymous=True) # ROS subscribers rospy.Subscriber("stm_command", String, self.stm_command_callback) - rospy.Subscriber("t") + + #rospy.Publisher("odom", anonymous=True) + self.tf2_broad = tf2_ros.TransformBroadcaster() super(STMnode, self).__init__(serial_port, baudrate) self.mutex = Lock() + + self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) + self.laser_angle = rospy.get_param('lidar_a') + + rospy.Timer(rospy.Duration(1. / ODOM_RATE), self.odom_callback) def stm_command_callback(self, data): cmd, args = self.parse_data(data) - successfully = self.send(cmd, args) - + successfully, values = self.send(cmd, args) + + def parse_data(self, data): data_splitted = data.data.split() cmd = int(data_splitted[0]) - args_dict = {'c': int, 'H': int, 'f': float} - args = [action_args_dict[t](s) for t, s in itertools.izip(pack_format[cmd][1:], data_splitted[1:])] + args_dict = {'c': str, 'H': int, 'f': float} + args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] return cmd, args def send(self, cmd, args): @@ -38,8 +51,44 @@ def send(self, cmd, args): successfully, values = self.send_command(cmd, args) self.mutex.release() rospy.loginfo('Got response args: '+ str(values)) - return successfully + return successfully, values + def odom_callback(self, event): + successfully, values = self.send(0x0F, args=None) + if successfully: + self.send_odometry(values) + + def send_odometry(self, values): + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot_odom" + t.child_frame_id = "secondary_robot" + t.transform.translation.x = values[0] + t.transform.translation.y = values[1] + t.transform.translation.z = 0.0 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, values[2]) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot" + t.child_frame_id = "secondary_robot_laser" + t.transform.translation.x = 0#self.laser_coords[0] + t.transform.translation.y = 0#self.laser_coords[1] + t.transform.translation.z = .4 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, 0)#self.laser_angle) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + if __name__ == '__main__': serial_port = "/dev/ttyUSB0" stm = STMnode(serial_port) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 479e162..b3c4ef0 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -6,7 +6,7 @@ class STMprotocol(object): def __init__(self,serial_port, baudrate=115200): - self.ser = serial(serial_port,baudrate=baudrate, timeout = 0.01) + self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) self.pack_format = { 0x01: "=cccc", 0x07: "=", @@ -19,28 +19,36 @@ def __init__(self,serial_port, baudrate=115200): self.unpack_format = { 0x01: "=cccc", 0x07: "=fff", - 0x08: "=cc", + 0x08: "=ccc", 0x09: "=fff", 0x0e: "=cc", 0x0f: "=fff", } + + self.response_bytes = { + 0x01: 4, + 0x07: 12, + 0x08: 2, + 0x09: 12, + 0x0e: 2, + 0x0f: 12, + } def pure_send_command(self, cmd, args): # Clear buffer self.ser.reset_output_buffer() self.ser.reset_input_buffer() # Sending command - parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) - print ('cmd=', cmd) - msg = bytearray([cmd]) + parameters - print ('msg = ' + str(struct.unpack('=cfff',msg))) + print ('msg=', cmd , args) + msg = bytearray([cmd]) + if args : + parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) + msg += parameters self.ser.write(msg) - - response = self.ser.readline() - print(response) + response = self.ser.read(self.response_bytes[cmd]+1) + print response if len(response) == 0: raise Exception("No data received") - values = struct.unpack(self.unpack_format[cmd], response) return True, values @@ -51,8 +59,9 @@ def send_command(self, cmd, args, n_repeats=5): return self.pure_send_command(cmd, args) except Exception as exc: if i == n_repeats - 1: - rospy.logerr('Exception:\t', exc) - rospy.logerr('At time:\t', datetime.datetime.now()) - rospy.logerr('cmd:', cmd, 'args:', args) - rospy.logerr('--------------------------') + rospy.loginfo('Exception:\t' + str(exc)) + rospy.loginfo('At time:\t' + str(datetime.datetime.now())) + rospy.loginfo('cmd:' + str(cmd) + 'args:' + str(args)) + #rospy.loginfo() + rospy.loginfo('--------------------------') return False, None From 74ef2ccd5bf58799fa0ba0f8aeafbbe7e8ea12eb Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 19 Dec 2018 18:48:43 +0300 Subject: [PATCH 05/40] trash was removed --- camera_test.py | 41 ----------------------------------------- 1 file changed, 41 deletions(-) delete mode 100755 camera_test.py diff --git a/camera_test.py b/camera_test.py deleted file mode 100755 index 8371b84..0000000 --- a/camera_test.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python - -from cv_bridge import CvBridge, CvBridgeError -import numpy as np -import cv2 -import roslib -import rospy -import sensor_msgs -import sys - -def callback(data): - try: - print(10) - br = CvBridge() - cv_image = br.imgmsg_to_cv2(data, "bgr8") - print(cv_image) - rospy.loginfo(rospy.get_caller_id()) - except CvBridgeError as e: - print(e) - - cv2.imshow("Image window", cv_image) - cv2.waitKey(3) - -def main(args): - print(1) - rospy.init_node('camera_test_node', anonymous=True) - print(2) - rospy.Subscriber("/usb_cam/image_raw", sensor_msgs.msg.Image, callback) - print(3) - try: - rospy.spin() - except KeyboardInterrupt: - print("Shutting down") - cv2.destroyAllWindows() - - -if __name__ == '__main__': - print(0) - main(sys.argv) - - From 36d79db3ab108ddec22a05337595f3f21fef1b04 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 19 Dec 2018 18:53:56 +0300 Subject: [PATCH 06/40] ... --- eurobot_camera/CMakeLists.txt | 199 ------- eurobot_camera/LICENSE | 674 ------------------------ eurobot_camera/launch/undistrort.launch | 16 - eurobot_camera/package.xml | 68 --- eurobot_camera/scripts/calibration.py | 65 --- eurobot_camera/scripts/undistort.py | 69 --- 6 files changed, 1091 deletions(-) delete mode 100644 eurobot_camera/CMakeLists.txt delete mode 100644 eurobot_camera/LICENSE delete mode 100644 eurobot_camera/launch/undistrort.launch delete mode 100644 eurobot_camera/package.xml delete mode 100755 eurobot_camera/scripts/calibration.py delete mode 100755 eurobot_camera/scripts/undistort.py diff --git a/eurobot_camera/CMakeLists.txt b/eurobot_camera/CMakeLists.txt deleted file mode 100644 index ce84372..0000000 --- a/eurobot_camera/CMakeLists.txt +++ /dev/null @@ -1,199 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(eurobot_camera) - -## Compile as C++11, supported in ROS Kinetic and newer -# add_compile_options(-std=c++11) - -## Find catkin macros and libraries -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) -## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS - roscpp - rospy - std_msgs -) - -## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) - - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -# catkin_python_setup() - -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a exec_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) - -## Generate messages in the 'msg' folder -# add_message_files( -# FILES -# Message1.msg -# Message2.msg -# ) - -## Generate services in the 'srv' folder -# add_service_files( -# FILES -# Service1.srv -# Service2.srv -# ) - -## Generate actions in the 'action' folder -# add_action_files( -# FILES -# Action1.action -# Action2.action -# ) - -## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# std_msgs -# ) - -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder -# generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg -# ) - -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if your package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( -# INCLUDE_DIRS include -# LIBRARIES eurobot_camera -# CATKIN_DEPENDS roscpp rospy std_msgs -# DEPENDS system_lib -) - -########### -## Build ## -########### - -## Specify additional locations of header files -## Your package locations should be listed before other locations -include_directories( -# include - ${catkin_INCLUDE_DIRS} -) - -## Declare a C++ library -# add_library(${PROJECT_NAME} -# src/${PROJECT_NAME}/eurobot_camera.cpp -# ) - -## Add cmake target dependencies of the library -## as an example, code may need to be generated before libraries -## either from message generation or dynamic reconfigure -# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Declare a C++ executable -## With catkin_make all packages are built within a single CMake context -## The recommended prefix ensures that target names across packages don't collide -# add_executable(${PROJECT_NAME}_node src/eurobot_camera_node.cpp) - -## Rename C++ executable without prefix -## The above recommended prefix causes long target names, the following renames the -## target back to the shorter version for ease of user use -## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" -# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") - -## Add cmake target dependencies of the executable -## same as for the library above -# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Specify libraries to link a library or executable target against -# target_link_libraries(${PROJECT_NAME}_node -# ${catkin_LIBRARIES} -# ) - -############# -## Install ## -############# - -# all install targets should use catkin DESTINATION variables -# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html - -## Mark executable scripts (Python etc.) for installation -## in contrast to setup.py, you can choose the destination -# install(PROGRAMS -# scripts/my_python_script -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark executables and/or libraries for installation -# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark cpp header files for installation -# install(DIRECTORY include/${PROJECT_NAME}/ -# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} -# FILES_MATCHING PATTERN "*.h" -# PATTERN ".svn" EXCLUDE -# ) - -## Mark other files for installation (e.g. launch and bag files, etc.) -# install(FILES -# # myfile1 -# # myfile2 -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -# ) - -############# -## Testing ## -############# - -## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_eurobot_camera.cpp) -# if(TARGET ${PROJECT_NAME}-test) -# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) -# endif() - -## Add folders to be run by python nosetests -# catkin_add_nosetests(test) diff --git a/eurobot_camera/LICENSE b/eurobot_camera/LICENSE deleted file mode 100644 index f288702..0000000 --- a/eurobot_camera/LICENSE +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/eurobot_camera/launch/undistrort.launch b/eurobot_camera/launch/undistrort.launch deleted file mode 100644 index cf6dceb..0000000 --- a/eurobot_camera/launch/undistrort.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/eurobot_camera/package.xml b/eurobot_camera/package.xml deleted file mode 100644 index c54d4a6..0000000 --- a/eurobot_camera/package.xml +++ /dev/null @@ -1,68 +0,0 @@ - - - eurobot_camera - 0.0.0 - The eurobot_camera package - - - - - alexey - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - roscpp - rospy - std_msgs - roscpp - rospy - std_msgs - roscpp - rospy - std_msgs - - - - - - - - diff --git a/eurobot_camera/scripts/calibration.py b/eurobot_camera/scripts/calibration.py deleted file mode 100755 index 4347057..0000000 --- a/eurobot_camera/scripts/calibration.py +++ /dev/null @@ -1,65 +0,0 @@ -import cv2 -import numpy as np -import os -import glob - -CHECKERBOARD = (7,4) - -# termination criteria -subpix_criteria = (cv2.TERM_CRITERIA_EPS+cv2.TERM_CRITERIA_MAX_ITER, 30, 0.1) -calibration_flags = cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC+cv2.fisheye.CALIB_CHECK_COND+cv2.fisheye.CALIB_FIX_SKEW - -objp = np.zeros((1, CHECKERBOARD[0]*CHECKERBOARD[1], 3), np.float32) -objp[0,:,:2] = np.mgrid[0:CHECKERBOARD[0], 0:CHECKERBOARD[1]].T.reshape(-1, 2) - -_img_shape = None -objpoints = [] # 3d point in real world space -imgpoints = [] # 2d points in image plane. - -images = glob.glob('*.png') - -for fname in images: - img = cv2.imread(fname) - if _img_shape == None: - _img_shape = img.shape[:2] - else: - assert _img_shape == img.shape[:2], "All images must share the same size." - gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) - # Find the chess board corners - ret, corners = cv2.findChessboardCorners(gray, CHECKERBOARD, None) - # If found, add object points, image points (after refining them) - if ret == True: - print(fname) - objpoints.append(objp) - cv2.cornerSubPix(gray,corners,(3,3),(-1,-1),subpix_criteria) - imgpoints.append(corners) - -N_OK = len(objpoints) -K = np.zeros((3, 3)) -D = np.zeros((4, 1)) -rvecs = [np.zeros((1, 1, 3), dtype=np.float64) for i in range(N_OK)] -tvecs = [np.zeros((1, 1, 3), dtype=np.float64) for i in range(N_OK)] -rms, _, _, _, _ = \ - cv2.fisheye.calibrate( - objpoints, - imgpoints, - gray.shape[::-1], - K, - D, - rvecs, - tvecs, - calibration_flags, - (cv2.TERM_CRITERIA_EPS+cv2.TERM_CRITERIA_MAX_ITER, 30, 1e-6) - ) - -print("Found " + str(N_OK) + " valid images for calibration") -print("DIM=" + str(_img_shape[::-1])) -print("K=np.array(" + str(K.tolist()) + ")") -print("D=np.array(" + str(D.tolist()) + ")") - -config_file = open('config','w') -config_file.write("Found " + str(N_OK) + " valid images for calibration \r\n") -config_file.write("DIM=" + str(_img_shape[::-1]) +'\r\n') -config_file.write("K=np.array(" + str(K.tolist()) + ") \r\n") -config_file.write("D=np.array(" + str(D.tolist()) + ") \r\n") - diff --git a/eurobot_camera/scripts/undistort.py b/eurobot_camera/scripts/undistort.py deleted file mode 100755 index b634ec4..0000000 --- a/eurobot_camera/scripts/undistort.py +++ /dev/null @@ -1,69 +0,0 @@ -#!/usr/bin/env python - -from cv_bridge import CvBridge, CvBridgeError -import numpy as np -import cv2 -import roslib -import rospy -import sensor_msgs -from sensor_msgs.msg import Image -import sys - -#FIXME: get coeff from file -DIM=(2448, 2048) -K=np.array([[677.6729654637016, 0.0, 1235.371481335309], [0.0, 679.4736576804626, 1043.9887347932538], [0.0, 0.0, 1.0]]) -D=np.array([[0.026055346132657364], [0.006035766757842894], [0.005666324884814231], [-0.0015661403498746557]]) - -#FIXME: create class to remove global values -image_pub = rospy.Publisher("MY_IMAGE_TOPIC",Image) - -def distortion(img,balance=0.0, dim2=None, dim3=None): - dim1 = img.shape[:2][::-1] #dim1 is the dimension of input image to un-distort - assert dim1[0]/dim1[1] == DIM[0]/DIM[1], "Image to undistort needs to have same aspect ratio as the ones used in calibration" - if not dim2: - dim2 = dim1 - if not dim3: - dim3 = dim1 - scaled_K = K * dim1[0] / DIM[0] # The values of K is to scale with image dimension. - scaled_K[2][2] = 1.0 # Except that K[2][2] is always 1.0 - # This is how scaled_K, dim2 and balance are used to determine the final K used to un-distort image. OpenCV document failed to make this clear! - new_K = cv2.fisheye.estimateNewCameraMatrixForUndistortRectify(scaled_K, D, dim2, np.eye(3), balance=balance) - map1, map2 = cv2.fisheye.initUndistortRectifyMap(scaled_K, D, np.eye(3), new_K, dim3, cv2.CV_16SC2) - undistorted_img = cv2.remap(img, map1, map2, interpolation=cv2.INTER_LINEAR, borderMode=cv2.BORDER_CONSTANT) - return undistorted_img - -def callback(data): - try: - print(10) - br = CvBridge() - cv_image = br.imgmsg_to_cv2(data, "bgr8") - print(cv_image) - rospy.loginfo(rospy.get_caller_id()) - except CvBridgeError as e: - print(e) - - image = distortion(cv_image) - try: - image_pub.publish(br.cv2_to_imgmsg(image, "bgr8")) - except CvBridgeError as e: - print(e) - -def talker(): - pub = rospy.Publisher('chatter', String, queue_size=10) - rospy.init_node('talker', anonymous=True) - rate = rospy.Rate(30) # 30hz - while not rospy.is_shutdown(): - hello_str = "hello world %s" % rospy.get_time() - rospy.loginfo(hello_str) - pub.publish(hello_str) - rate.sleep() - -rospy.init_node('camera_main_node', anonymous=True) -rospy.Subscriber("/usb_cam/image_raw", sensor_msgs.msg.Image, callback) -try: - rospy.spin() -except KeyboardInterrupt: - print("Shutting down") -cv2.destroyAllWindows() - - From 709812b2db055cd20f4ee7958c21d45277b09322 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 19 Dec 2018 19:38:39 +0300 Subject: [PATCH 07/40] add new commands to protocol --- eurobot_stm/scripts/STM_protocol.py | 29 ++++++++++++++++++++++------- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index b3c4ef0..af41509 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -14,6 +14,11 @@ def __init__(self,serial_port, baudrate=115200): 0x09: "=", 0x0e: "=fff", 0x0f: "=", + 0x10: "=", + 0x11: "=", + 0x12: "=", + 0x13: "=", + 0x14: "=" } self.unpack_format = { @@ -23,30 +28,40 @@ def __init__(self,serial_port, baudrate=115200): 0x09: "=fff", 0x0e: "=cc", 0x0f: "=fff", + 0x10: "=cc", + 0x11: "=cc", + 0x12: "=cc", + 0x13: "=cc", + 0x14: "=cc" } - - self.response_bytes = { - 0x01: 4, + + self.response_bytes = { + 0x01: 4, 0x07: 12, - 0x08: 2, + 0x08: 2, 0x09: 12, 0x0e: 2, 0x0f: 12, - } + 0x10: 2, + 0x11: 2, + 0x12: 2, + 0x13: 2, + 0x14: 2 + } def pure_send_command(self, cmd, args): # Clear buffer self.ser.reset_output_buffer() self.ser.reset_input_buffer() # Sending command - print ('msg=', cmd , args) + print ('msg=', cmd , args) msg = bytearray([cmd]) if args : parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) msg += parameters self.ser.write(msg) response = self.ser.read(self.response_bytes[cmd]+1) - print response + print response if len(response) == 0: raise Exception("No data received") values = struct.unpack(self.unpack_format[cmd], response) From 2812d2eec4dfdef3204bb7c47eea9a24434e5827 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Fri, 25 Jan 2019 17:47:28 +0300 Subject: [PATCH 08/40] new architecture. add odometry, manipulator files. add launch file --- eurobot_stm/launch/STM_node.launch | 8 +++ eurobot_stm/scripts/STM.py | 40 ++++++++++++ eurobot_stm/scripts/STM_node.py | 95 ----------------------------- eurobot_stm/scripts/STM_protocol.py | 14 ++++- eurobot_stm/scripts/manipulator.py | 1 + eurobot_stm/scripts/odometry.py | 54 ++++++++++++++++ 6 files changed, 115 insertions(+), 97 deletions(-) create mode 100644 eurobot_stm/launch/STM_node.launch create mode 100755 eurobot_stm/scripts/STM.py delete mode 100755 eurobot_stm/scripts/STM_node.py create mode 100755 eurobot_stm/scripts/manipulator.py create mode 100755 eurobot_stm/scripts/odometry.py diff --git a/eurobot_stm/launch/STM_node.launch b/eurobot_stm/launch/STM_node.launch new file mode 100644 index 0000000..ac18e82 --- /dev/null +++ b/eurobot_stm/launch/STM_node.launch @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py new file mode 100755 index 0000000..e1ecce6 --- /dev/null +++ b/eurobot_stm/scripts/STM.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python +import rospy +from std_msgs.msg import String +from threading import Lock + +import serial +import itertools +from STM_protocol import STMprotocol +import odometry + +ODOM_RATE = 40 # Hz + +class STM(): + def __init__(self, serial_port, baudrate=115200): + # Init ROS + rospy.init_node('stm_node', anonymous=True) + # ROS subscribers + rospy.Subscriber("stm_command", String, self.stm_command_callback) + + self.stm_protocol = STMprotocol(serial_port, baudrate) + self.odometry = Odometry(self.stm_protocol, ODOM_RATE) + + self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) + self.laser_angle = rospy.get_param('lidar_a') + + def stm_command_callback(self, data): + cmd, args = self.parse_data(data) + successfully, values = self.stm_protocol.send(cmd, args) + + def parse_data(self, data): + data_splitted = data.data.split() + cmd = int(data_splitted[0]) + args_dict = {'c': str, 'H': int, 'f': float} + args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] + return cmd, args + +if __name__ == '__main__': + serial_port = "/dev/ttyUSB0" + stm = STM(serial_port) + rospy.spin() diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py deleted file mode 100755 index c8460e4..0000000 --- a/eurobot_stm/scripts/STM_node.py +++ /dev/null @@ -1,95 +0,0 @@ -#!/usr/bin/env python -import rospy -from std_msgs.msg import String -from threading import Lock -from std_msgs.msg import Int32MultiArray -import geometry_msgs.msg -import tf_conversions -import tf2_ros -import numpy as np -import datetime -import time -import struct -import serial -import itertools -from STM_protocol import STMprotocol - -ODOM_RATE = 40 # Hz - -class STMnode(STMprotocol): - def __init__(self, serial_port, baudrate=115200): - # Init ROS - rospy.init_node('stm_node', anonymous=True) - # ROS subscribers - rospy.Subscriber("stm_command", String, self.stm_command_callback) - - #rospy.Publisher("odom", anonymous=True) - self.tf2_broad = tf2_ros.TransformBroadcaster() - - super(STMnode, self).__init__(serial_port, baudrate) - self.mutex = Lock() - - self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) - self.laser_angle = rospy.get_param('lidar_a') - - rospy.Timer(rospy.Duration(1. / ODOM_RATE), self.odom_callback) - - def stm_command_callback(self, data): - cmd, args = self.parse_data(data) - successfully, values = self.send(cmd, args) - - - def parse_data(self, data): - data_splitted = data.data.split() - cmd = int(data_splitted[0]) - args_dict = {'c': str, 'H': int, 'f': float} - args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] - return cmd, args - - def send(self, cmd, args): - self.mutex.acquire() - successfully, values = self.send_command(cmd, args) - self.mutex.release() - rospy.loginfo('Got response args: '+ str(values)) - return successfully, values - - def odom_callback(self, event): - successfully, values = self.send(0x0F, args=None) - if successfully: - self.send_odometry(values) - - def send_odometry(self, values): - t = geometry_msgs.msg.TransformStamped() - t.header.stamp = rospy.Time.now() - t.header.frame_id = "secondary_robot_odom" - t.child_frame_id = "secondary_robot" - t.transform.translation.x = values[0] - t.transform.translation.y = values[1] - t.transform.translation.z = 0.0 - q = tf_conversions.transformations.quaternion_from_euler(0, 0, values[2]) - t.transform.rotation.x = q[0] - t.transform.rotation.y = q[1] - t.transform.rotation.z = q[2] - t.transform.rotation.w = q[3] - - self.tf2_broad.sendTransform(t) - - t = geometry_msgs.msg.TransformStamped() - t.header.stamp = rospy.Time.now() - t.header.frame_id = "secondary_robot" - t.child_frame_id = "secondary_robot_laser" - t.transform.translation.x = 0#self.laser_coords[0] - t.transform.translation.y = 0#self.laser_coords[1] - t.transform.translation.z = .4 - q = tf_conversions.transformations.quaternion_from_euler(0, 0, 0)#self.laser_angle) - t.transform.rotation.x = q[0] - t.transform.rotation.y = q[1] - t.transform.rotation.z = q[2] - t.transform.rotation.w = q[3] - - self.tf2_broad.sendTransform(t) - -if __name__ == '__main__': - serial_port = "/dev/ttyUSB0" - stm = STMnode(serial_port) - rospy.spin() diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index af41509..f565177 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -5,7 +5,10 @@ import rospy class STMprotocol(object): - def __init__(self,serial_port, baudrate=115200): + def __init__(self, serial_port, baudrate=115200): + + self.mutex = Lock() + self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) self.pack_format = { 0x01: "=cccc", @@ -48,7 +51,14 @@ def __init__(self,serial_port, baudrate=115200): 0x13: 2, 0x14: 2 } - + + def send(self, cmd, args): + self.mutex.acquire() + successfully, values = self.send_command(cmd, args) + self.mutex.release() + rospy.loginfo('Got response args: '+ str(values)) + return successfully, values + def pure_send_command(self, cmd, args): # Clear buffer self.ser.reset_output_buffer() diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py new file mode 100755 index 0000000..4265cc3 --- /dev/null +++ b/eurobot_stm/scripts/manipulator.py @@ -0,0 +1 @@ +#!/usr/bin/env python diff --git a/eurobot_stm/scripts/odometry.py b/eurobot_stm/scripts/odometry.py new file mode 100755 index 0000000..de75c26 --- /dev/null +++ b/eurobot_stm/scripts/odometry.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python +import rospy +import geometry_msgs.msg +import tf_conversions +import tf2_ros +import STM_protocol + + +class Odometry(): + def __init__(self, rate=40, stm_protocol): + self.tf2_broad = tf2_ros.TransformBroadcaster() + self.stm_protocol = stm_protocol + + rospy.Timer(rospy.Duration(1. / rate), self.odom_callback) + + + def odom_callback(self, event): + self.stm_protocol.send(0x0F, args=None) + if successfully: + self.send_odometry(values) + + + def send_odometry(self, values): + rospy.loginfo("odom: %.3f %.3f %.3f" % tuple(values)) + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot_odom" + t.child_frame_id = "secondary_robot" + t.transform.translation.x = values[0] + t.transform.translation.y = values[1] + t.transform.translation.z = 0.0 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, values[2]) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot" + t.child_frame_id = "secondary_robot_laser" + t.transform.translation.x = 0#self.laser_coords[0] + t.transform.translation.y = 0#self.laser_coords[1] + t.transform.translation.z = .4 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, 0)#self.laser_angle) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + From 277836d6661bf0641d8801830b49e61c9d1b1605 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Mon, 28 Jan 2019 17:02:00 +0300 Subject: [PATCH 09/40] add jupyter files. minor changes --- .../Untitled-checkpoint.ipynb | 6 ++ eurobot_stm/jupyter/STM.py | 40 ++++++++ eurobot_stm/jupyter/STM_protocol.py | 94 +++++++++++++++++++ eurobot_stm/jupyter/Untitled.ipynb | 85 +++++++++++++++++ eurobot_stm/jupyter/manipulator.py | 1 + eurobot_stm/jupyter/odometry.py | 54 +++++++++++ eurobot_stm/scripts/STM.py | 9 +- eurobot_stm/scripts/STM_protocol.py | 2 + eurobot_stm/scripts/odometry.py | 2 +- 9 files changed, 286 insertions(+), 7 deletions(-) create mode 100644 eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb create mode 100755 eurobot_stm/jupyter/STM.py create mode 100755 eurobot_stm/jupyter/STM_protocol.py create mode 100644 eurobot_stm/jupyter/Untitled.ipynb create mode 100755 eurobot_stm/jupyter/manipulator.py create mode 100755 eurobot_stm/jupyter/odometry.py diff --git a/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb b/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb new file mode 100644 index 0000000..2fd6442 --- /dev/null +++ b/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb @@ -0,0 +1,6 @@ +{ + "cells": [], + "metadata": {}, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/eurobot_stm/jupyter/STM.py b/eurobot_stm/jupyter/STM.py new file mode 100755 index 0000000..e1ecce6 --- /dev/null +++ b/eurobot_stm/jupyter/STM.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python +import rospy +from std_msgs.msg import String +from threading import Lock + +import serial +import itertools +from STM_protocol import STMprotocol +import odometry + +ODOM_RATE = 40 # Hz + +class STM(): + def __init__(self, serial_port, baudrate=115200): + # Init ROS + rospy.init_node('stm_node', anonymous=True) + # ROS subscribers + rospy.Subscriber("stm_command", String, self.stm_command_callback) + + self.stm_protocol = STMprotocol(serial_port, baudrate) + self.odometry = Odometry(self.stm_protocol, ODOM_RATE) + + self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) + self.laser_angle = rospy.get_param('lidar_a') + + def stm_command_callback(self, data): + cmd, args = self.parse_data(data) + successfully, values = self.stm_protocol.send(cmd, args) + + def parse_data(self, data): + data_splitted = data.data.split() + cmd = int(data_splitted[0]) + args_dict = {'c': str, 'H': int, 'f': float} + args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] + return cmd, args + +if __name__ == '__main__': + serial_port = "/dev/ttyUSB0" + stm = STM(serial_port) + rospy.spin() diff --git a/eurobot_stm/jupyter/STM_protocol.py b/eurobot_stm/jupyter/STM_protocol.py new file mode 100755 index 0000000..ded96f4 --- /dev/null +++ b/eurobot_stm/jupyter/STM_protocol.py @@ -0,0 +1,94 @@ +import serial +import struct +import time +import datetime +import rospy +from threading import Lock + + +class STMprotocol(object): + def __init__(self, serial_port, baudrate=115200): + + self.mutex = Lock() + + self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) + self.pack_format = { + 0x01: "=cccc", + 0x07: "=", + 0x08: "=fff", + 0x09: "=", + 0x0e: "=fff", + 0x0f: "=", + 0x10: "=", + 0x11: "=", + 0x12: "=", + 0x13: "=", + 0x14: "=" + } + + self.unpack_format = { + 0x01: "=cccc", + 0x07: "=fff", + 0x08: "=ccc", + 0x09: "=fff", + 0x0e: "=cc", + 0x0f: "=fff", + 0x10: "=cc", + 0x11: "=cc", + 0x12: "=cc", + 0x13: "=cc", + 0x14: "=cc" + } + + self.response_bytes = { + 0x01: 4, + 0x07: 12, + 0x08: 2, + 0x09: 12, + 0x0e: 2, + 0x0f: 12, + 0x10: 2, + 0x11: 2, + 0x12: 2, + 0x13: 2, + 0x14: 2 + } + + def send(self, cmd, args): + self.mutex.acquire() + successfully, values = self.send_command(cmd, args) + self.mutex.release() + rospy.loginfo('Got response args: '+ str(values)) + return successfully, values + + def pure_send_command(self, cmd, args): + # Clear buffer + self.ser.reset_output_buffer() + self.ser.reset_input_buffer() + # Sending command + print ('msg=', cmd , args) + msg = bytearray([cmd]) + if args : + parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) + msg += parameters + self.ser.write(msg) + response = self.ser.read(self.response_bytes[cmd]+1) + print response + if len(response) == 0: + raise Exception("No data received") + values = struct.unpack(self.unpack_format[cmd], response) + return True, values + + + def send_command(self, cmd, args, n_repeats=5): + for i in range(n_repeats): + try: + return self.pure_send_command(cmd, args) + except Exception as exc: + if i == n_repeats - 1: + rospy.loginfo('Exception:\t' + str(exc)) + rospy.loginfo('At time:\t' + str(datetime.datetime.now())) + rospy.loginfo('cmd:' + str(cmd) + 'args:' + str(args)) + #rospy.loginfo() + rospy.loginfo('--------------------------') + return False, None diff --git a/eurobot_stm/jupyter/Untitled.ipynb b/eurobot_stm/jupyter/Untitled.ipynb new file mode 100644 index 0000000..547559e --- /dev/null +++ b/eurobot_stm/jupyter/Untitled.ipynb @@ -0,0 +1,85 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "ename": "SerialException", + "evalue": "[Errno 2] could not open port /dev/ttyUSB0: [Errno 2] No such file or directory: '/dev/ttyUSB0'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mSerialException\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m()\u001b[0m\n\u001b[1;32m 33\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0m__name__\u001b[0m \u001b[0;34m==\u001b[0m \u001b[0;34m'__main__'\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 34\u001b[0m \u001b[0mserial_port\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m\"/dev/ttyUSB0\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 35\u001b[0;31m \u001b[0mstm\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mSTM\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 36\u001b[0m \u001b[0mrospy\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mspin\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;32m\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, serial_port, baudrate)\u001b[0m\n\u001b[1;32m 17\u001b[0m \u001b[0mrospy\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mSubscriber\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m\"stm_command\"\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mString\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_command_callback\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 18\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 19\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_protocol\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mSTMprotocol\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mbaudrate\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 20\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0modometry\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mOdometry\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_protocol\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mODOM_RATE\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 21\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;32m/home/theta/catkin_ws/src/ros-eurobot-2019/eurobot_stm/jupyter/STM_protocol.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, serial_port, baudrate)\u001b[0m\n\u001b[1;32m 12\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmutex\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mLock\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 13\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 14\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mser\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mserial\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mSerial\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mbaudrate\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mbaudrate\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mtimeout\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;36m0.01\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 15\u001b[0m self.pack_format = {\n\u001b[1;32m 16\u001b[0m \u001b[0;36m0x01\u001b[0m\u001b[0;34m:\u001b[0m \u001b[0;34m\"=cccc\"\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;32m/usr/lib/python2.7/dist-packages/serial/serialutil.pyc\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, port, baudrate, bytesize, parity, stopbits, timeout, xonxoff, rtscts, write_timeout, dsrdtr, inter_byte_timeout, **kwargs)\u001b[0m\n\u001b[1;32m 178\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 179\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mport\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 180\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 181\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 182\u001b[0m \u001b[0;31m# - - - - - - - - - - - - - - - - - - - - - - - -\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;32m/usr/lib/python2.7/dist-packages/serial/serialposix.pyc\u001b[0m in \u001b[0;36mopen\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 292\u001b[0m \u001b[0;32mexcept\u001b[0m \u001b[0mOSError\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mmsg\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 293\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfd\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mNone\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 294\u001b[0;31m \u001b[0;32mraise\u001b[0m \u001b[0mSerialException\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mmsg\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0merrno\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m\"could not open port %s: %s\"\u001b[0m \u001b[0;34m%\u001b[0m \u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_port\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mmsg\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 295\u001b[0m \u001b[0;31m#~ fcntl.fcntl(self.fd, fcntl.F_SETFL, 0) # set blocking\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 296\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;31mSerialException\u001b[0m: [Errno 2] could not open port /dev/ttyUSB0: [Errno 2] No such file or directory: '/dev/ttyUSB0'" + ] + } + ], + "source": [ + "#!/usr/bin/env python\n", + "import rospy\n", + "from std_msgs.msg import String\n", + "\n", + "import serial\n", + "import itertools\n", + "from STM_protocol import STMprotocol\n", + "import odometry\n", + "\n", + "ODOM_RATE = 40 # Hz\n", + "\n", + "class STM():\n", + " def __init__(self, serial_port, baudrate=115200):\n", + " # Init ROS\n", + " rospy.init_node('stm_node', anonymous=True)\n", + " # ROS subscribers\n", + " rospy.Subscriber(\"stm_command\", String, self.stm_command_callback) \n", + "\n", + " self.stm_protocol = STMprotocol(serial_port, baudrate)\n", + " self.odometry = Odometry(self.stm_protocol, ODOM_RATE)\n", + " \n", + " def stm_command_callback(self, data):\n", + " cmd, args = self.parse_data(data)\n", + " successfully, values = self.stm_protocol.send(cmd, args)\n", + "\n", + " def parse_data(self, data):\n", + " data_splitted = data.data.split()\n", + " cmd = int(data_splitted[0])\n", + " args_dict = {'c': str, 'H': int, 'f': float}\n", + " args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])]\n", + " return cmd, args\n", + "\n", + "if __name__ == '__main__':\n", + " serial_port = \"/dev/ttyUSB0\"\n", + " stm = STM(serial_port)\n", + " rospy.spin()\n" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.12" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/eurobot_stm/jupyter/manipulator.py b/eurobot_stm/jupyter/manipulator.py new file mode 100755 index 0000000..4265cc3 --- /dev/null +++ b/eurobot_stm/jupyter/manipulator.py @@ -0,0 +1 @@ +#!/usr/bin/env python diff --git a/eurobot_stm/jupyter/odometry.py b/eurobot_stm/jupyter/odometry.py new file mode 100755 index 0000000..9bd19f2 --- /dev/null +++ b/eurobot_stm/jupyter/odometry.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python +import rospy +import geometry_msgs.msg +import tf_conversions +import tf2_ros +import STM_protocol + + +class Odometry(): + def __init__(self, stm_protocol, rate): + self.tf2_broad = tf2_ros.TransformBroadcaster() + self.stm_protocol = stm_protocol + + rospy.Timer(rospy.Duration(1. / rate), self.odom_callback) + + + def odom_callback(self, event): + self.stm_protocol.send(0x0F, args=None) + if successfully: + self.send_odometry(values) + + + def send_odometry(self, values): + rospy.loginfo("odom: %.3f %.3f %.3f" % tuple(values)) + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot_odom" + t.child_frame_id = "secondary_robot" + t.transform.translation.x = values[0] + t.transform.translation.y = values[1] + t.transform.translation.z = 0.0 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, values[2]) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + + t = geometry_msgs.msg.TransformStamped() + t.header.stamp = rospy.Time.now() + t.header.frame_id = "secondary_robot" + t.child_frame_id = "secondary_robot_laser" + t.transform.translation.x = 0#self.laser_coords[0] + t.transform.translation.y = 0#self.laser_coords[1] + t.transform.translation.z = .4 + q = tf_conversions.transformations.quaternion_from_euler(0, 0, 0)#self.laser_angle) + t.transform.rotation.x = q[0] + t.transform.rotation.y = q[1] + t.transform.rotation.z = q[2] + t.transform.rotation.w = q[3] + + self.tf2_broad.sendTransform(t) + diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index e1ecce6..7ea316e 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -1,7 +1,6 @@ #!/usr/bin/env python import rospy from std_msgs.msg import String -from threading import Lock import serial import itertools @@ -17,11 +16,8 @@ def __init__(self, serial_port, baudrate=115200): # ROS subscribers rospy.Subscriber("stm_command", String, self.stm_command_callback) - self.stm_protocol = STMprotocol(serial_port, baudrate) - self.odometry = Odometry(self.stm_protocol, ODOM_RATE) - - self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) - self.laser_angle = rospy.get_param('lidar_a') + self.stm_protocol = STMprotocol(serial_port, baudrate) + self.odometry = Odometry(self.stm_protocol, ODOM_RATE) def stm_command_callback(self, data): cmd, args = self.parse_data(data) @@ -38,3 +34,4 @@ def parse_data(self, data): serial_port = "/dev/ttyUSB0" stm = STM(serial_port) rospy.spin() + diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index f565177..83a3994 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -4,6 +4,8 @@ import datetime import rospy +from threading import Lock + class STMprotocol(object): def __init__(self, serial_port, baudrate=115200): diff --git a/eurobot_stm/scripts/odometry.py b/eurobot_stm/scripts/odometry.py index de75c26..9bd19f2 100755 --- a/eurobot_stm/scripts/odometry.py +++ b/eurobot_stm/scripts/odometry.py @@ -7,7 +7,7 @@ class Odometry(): - def __init__(self, rate=40, stm_protocol): + def __init__(self, stm_protocol, rate): self.tf2_broad = tf2_ros.TransformBroadcaster() self.stm_protocol = stm_protocol From bbc00bf219979d9f5b1b9cb891b98aa4d4e47229 Mon Sep 17 00:00:00 2001 From: nickzherdev Date: Mon, 28 Jan 2019 20:53:21 +0300 Subject: [PATCH 10/40] minor changes --- .../Untitled-checkpoint.ipynb | 6 -- eurobot_stm/jupyter/STM.py | 40 -------- eurobot_stm/jupyter/STM_protocol.py | 94 ------------------- eurobot_stm/jupyter/Untitled.ipynb | 85 ----------------- eurobot_stm/jupyter/manipulator.py | 1 - eurobot_stm/jupyter/odometry.py | 54 ----------- eurobot_stm/scripts/STM.py | 4 +- eurobot_stm/scripts/STM_protocol.py | 18 +++- eurobot_stm/scripts/manipulator.py | 40 ++++++++ eurobot_stm/scripts/odometry.py | 2 +- 10 files changed, 58 insertions(+), 286 deletions(-) delete mode 100644 eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb delete mode 100755 eurobot_stm/jupyter/STM.py delete mode 100755 eurobot_stm/jupyter/STM_protocol.py delete mode 100644 eurobot_stm/jupyter/Untitled.ipynb delete mode 100755 eurobot_stm/jupyter/manipulator.py delete mode 100755 eurobot_stm/jupyter/odometry.py diff --git a/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb b/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb deleted file mode 100644 index 2fd6442..0000000 --- a/eurobot_stm/jupyter/.ipynb_checkpoints/Untitled-checkpoint.ipynb +++ /dev/null @@ -1,6 +0,0 @@ -{ - "cells": [], - "metadata": {}, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/eurobot_stm/jupyter/STM.py b/eurobot_stm/jupyter/STM.py deleted file mode 100755 index e1ecce6..0000000 --- a/eurobot_stm/jupyter/STM.py +++ /dev/null @@ -1,40 +0,0 @@ -#!/usr/bin/env python -import rospy -from std_msgs.msg import String -from threading import Lock - -import serial -import itertools -from STM_protocol import STMprotocol -import odometry - -ODOM_RATE = 40 # Hz - -class STM(): - def __init__(self, serial_port, baudrate=115200): - # Init ROS - rospy.init_node('stm_node', anonymous=True) - # ROS subscribers - rospy.Subscriber("stm_command", String, self.stm_command_callback) - - self.stm_protocol = STMprotocol(serial_port, baudrate) - self.odometry = Odometry(self.stm_protocol, ODOM_RATE) - - self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) - self.laser_angle = rospy.get_param('lidar_a') - - def stm_command_callback(self, data): - cmd, args = self.parse_data(data) - successfully, values = self.stm_protocol.send(cmd, args) - - def parse_data(self, data): - data_splitted = data.data.split() - cmd = int(data_splitted[0]) - args_dict = {'c': str, 'H': int, 'f': float} - args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] - return cmd, args - -if __name__ == '__main__': - serial_port = "/dev/ttyUSB0" - stm = STM(serial_port) - rospy.spin() diff --git a/eurobot_stm/jupyter/STM_protocol.py b/eurobot_stm/jupyter/STM_protocol.py deleted file mode 100755 index ded96f4..0000000 --- a/eurobot_stm/jupyter/STM_protocol.py +++ /dev/null @@ -1,94 +0,0 @@ -import serial -import struct -import time -import datetime -import rospy -from threading import Lock - - -class STMprotocol(object): - def __init__(self, serial_port, baudrate=115200): - - self.mutex = Lock() - - self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) - self.pack_format = { - 0x01: "=cccc", - 0x07: "=", - 0x08: "=fff", - 0x09: "=", - 0x0e: "=fff", - 0x0f: "=", - 0x10: "=", - 0x11: "=", - 0x12: "=", - 0x13: "=", - 0x14: "=" - } - - self.unpack_format = { - 0x01: "=cccc", - 0x07: "=fff", - 0x08: "=ccc", - 0x09: "=fff", - 0x0e: "=cc", - 0x0f: "=fff", - 0x10: "=cc", - 0x11: "=cc", - 0x12: "=cc", - 0x13: "=cc", - 0x14: "=cc" - } - - self.response_bytes = { - 0x01: 4, - 0x07: 12, - 0x08: 2, - 0x09: 12, - 0x0e: 2, - 0x0f: 12, - 0x10: 2, - 0x11: 2, - 0x12: 2, - 0x13: 2, - 0x14: 2 - } - - def send(self, cmd, args): - self.mutex.acquire() - successfully, values = self.send_command(cmd, args) - self.mutex.release() - rospy.loginfo('Got response args: '+ str(values)) - return successfully, values - - def pure_send_command(self, cmd, args): - # Clear buffer - self.ser.reset_output_buffer() - self.ser.reset_input_buffer() - # Sending command - print ('msg=', cmd , args) - msg = bytearray([cmd]) - if args : - parameters = bytearray(struct.pack(self.pack_format[cmd], *args)) - msg += parameters - self.ser.write(msg) - response = self.ser.read(self.response_bytes[cmd]+1) - print response - if len(response) == 0: - raise Exception("No data received") - values = struct.unpack(self.unpack_format[cmd], response) - return True, values - - - def send_command(self, cmd, args, n_repeats=5): - for i in range(n_repeats): - try: - return self.pure_send_command(cmd, args) - except Exception as exc: - if i == n_repeats - 1: - rospy.loginfo('Exception:\t' + str(exc)) - rospy.loginfo('At time:\t' + str(datetime.datetime.now())) - rospy.loginfo('cmd:' + str(cmd) + 'args:' + str(args)) - #rospy.loginfo() - rospy.loginfo('--------------------------') - return False, None diff --git a/eurobot_stm/jupyter/Untitled.ipynb b/eurobot_stm/jupyter/Untitled.ipynb deleted file mode 100644 index 547559e..0000000 --- a/eurobot_stm/jupyter/Untitled.ipynb +++ /dev/null @@ -1,85 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "ename": "SerialException", - "evalue": "[Errno 2] could not open port /dev/ttyUSB0: [Errno 2] No such file or directory: '/dev/ttyUSB0'", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mSerialException\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m()\u001b[0m\n\u001b[1;32m 33\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0m__name__\u001b[0m \u001b[0;34m==\u001b[0m \u001b[0;34m'__main__'\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 34\u001b[0m \u001b[0mserial_port\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m\"/dev/ttyUSB0\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 35\u001b[0;31m \u001b[0mstm\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mSTM\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 36\u001b[0m \u001b[0mrospy\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mspin\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, serial_port, baudrate)\u001b[0m\n\u001b[1;32m 17\u001b[0m \u001b[0mrospy\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mSubscriber\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m\"stm_command\"\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mString\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_command_callback\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 18\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 19\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_protocol\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mSTMprotocol\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mbaudrate\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 20\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0modometry\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mOdometry\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mstm_protocol\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mODOM_RATE\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 21\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m/home/theta/catkin_ws/src/ros-eurobot-2019/eurobot_stm/jupyter/STM_protocol.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, serial_port, baudrate)\u001b[0m\n\u001b[1;32m 12\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmutex\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mLock\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 13\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 14\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mser\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mserial\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mSerial\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mserial_port\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mbaudrate\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mbaudrate\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mtimeout\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;36m0.01\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 15\u001b[0m self.pack_format = {\n\u001b[1;32m 16\u001b[0m \u001b[0;36m0x01\u001b[0m\u001b[0;34m:\u001b[0m \u001b[0;34m\"=cccc\"\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m/usr/lib/python2.7/dist-packages/serial/serialutil.pyc\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, port, baudrate, bytesize, parity, stopbits, timeout, xonxoff, rtscts, write_timeout, dsrdtr, inter_byte_timeout, **kwargs)\u001b[0m\n\u001b[1;32m 178\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 179\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mport\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 180\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 181\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 182\u001b[0m \u001b[0;31m# - - - - - - - - - - - - - - - - - - - - - - - -\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m/usr/lib/python2.7/dist-packages/serial/serialposix.pyc\u001b[0m in \u001b[0;36mopen\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 292\u001b[0m \u001b[0;32mexcept\u001b[0m \u001b[0mOSError\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mmsg\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 293\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfd\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mNone\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 294\u001b[0;31m \u001b[0;32mraise\u001b[0m \u001b[0mSerialException\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mmsg\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0merrno\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m\"could not open port %s: %s\"\u001b[0m \u001b[0;34m%\u001b[0m \u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_port\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mmsg\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 295\u001b[0m \u001b[0;31m#~ fcntl.fcntl(self.fd, fcntl.F_SETFL, 0) # set blocking\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 296\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;31mSerialException\u001b[0m: [Errno 2] could not open port /dev/ttyUSB0: [Errno 2] No such file or directory: '/dev/ttyUSB0'" - ] - } - ], - "source": [ - "#!/usr/bin/env python\n", - "import rospy\n", - "from std_msgs.msg import String\n", - "\n", - "import serial\n", - "import itertools\n", - "from STM_protocol import STMprotocol\n", - "import odometry\n", - "\n", - "ODOM_RATE = 40 # Hz\n", - "\n", - "class STM():\n", - " def __init__(self, serial_port, baudrate=115200):\n", - " # Init ROS\n", - " rospy.init_node('stm_node', anonymous=True)\n", - " # ROS subscribers\n", - " rospy.Subscriber(\"stm_command\", String, self.stm_command_callback) \n", - "\n", - " self.stm_protocol = STMprotocol(serial_port, baudrate)\n", - " self.odometry = Odometry(self.stm_protocol, ODOM_RATE)\n", - " \n", - " def stm_command_callback(self, data):\n", - " cmd, args = self.parse_data(data)\n", - " successfully, values = self.stm_protocol.send(cmd, args)\n", - "\n", - " def parse_data(self, data):\n", - " data_splitted = data.data.split()\n", - " cmd = int(data_splitted[0])\n", - " args_dict = {'c': str, 'H': int, 'f': float}\n", - " args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])]\n", - " return cmd, args\n", - "\n", - "if __name__ == '__main__':\n", - " serial_port = \"/dev/ttyUSB0\"\n", - " stm = STM(serial_port)\n", - " rospy.spin()\n" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 2", - "language": "python", - "name": "python2" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 2 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.12" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/eurobot_stm/jupyter/manipulator.py b/eurobot_stm/jupyter/manipulator.py deleted file mode 100755 index 4265cc3..0000000 --- a/eurobot_stm/jupyter/manipulator.py +++ /dev/null @@ -1 +0,0 @@ -#!/usr/bin/env python diff --git a/eurobot_stm/jupyter/odometry.py b/eurobot_stm/jupyter/odometry.py deleted file mode 100755 index 9bd19f2..0000000 --- a/eurobot_stm/jupyter/odometry.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python -import rospy -import geometry_msgs.msg -import tf_conversions -import tf2_ros -import STM_protocol - - -class Odometry(): - def __init__(self, stm_protocol, rate): - self.tf2_broad = tf2_ros.TransformBroadcaster() - self.stm_protocol = stm_protocol - - rospy.Timer(rospy.Duration(1. / rate), self.odom_callback) - - - def odom_callback(self, event): - self.stm_protocol.send(0x0F, args=None) - if successfully: - self.send_odometry(values) - - - def send_odometry(self, values): - rospy.loginfo("odom: %.3f %.3f %.3f" % tuple(values)) - t = geometry_msgs.msg.TransformStamped() - t.header.stamp = rospy.Time.now() - t.header.frame_id = "secondary_robot_odom" - t.child_frame_id = "secondary_robot" - t.transform.translation.x = values[0] - t.transform.translation.y = values[1] - t.transform.translation.z = 0.0 - q = tf_conversions.transformations.quaternion_from_euler(0, 0, values[2]) - t.transform.rotation.x = q[0] - t.transform.rotation.y = q[1] - t.transform.rotation.z = q[2] - t.transform.rotation.w = q[3] - - self.tf2_broad.sendTransform(t) - - t = geometry_msgs.msg.TransformStamped() - t.header.stamp = rospy.Time.now() - t.header.frame_id = "secondary_robot" - t.child_frame_id = "secondary_robot_laser" - t.transform.translation.x = 0#self.laser_coords[0] - t.transform.translation.y = 0#self.laser_coords[1] - t.transform.translation.z = .4 - q = tf_conversions.transformations.quaternion_from_euler(0, 0, 0)#self.laser_angle) - t.transform.rotation.x = q[0] - t.transform.rotation.y = q[1] - t.transform.rotation.z = q[2] - t.transform.rotation.w = q[3] - - self.tf2_broad.sendTransform(t) - diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index 7ea316e..be9b17a 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -17,7 +17,7 @@ def __init__(self, serial_port, baudrate=115200): rospy.Subscriber("stm_command", String, self.stm_command_callback) self.stm_protocol = STMprotocol(serial_port, baudrate) - self.odometry = Odometry(self.stm_protocol, ODOM_RATE) +# self.odometry = odometry.Odometry(self.stm_protocol, ODOM_RATE) def stm_command_callback(self, data): cmd, args = self.parse_data(data) @@ -27,7 +27,7 @@ def parse_data(self, data): data_splitted = data.data.split() cmd = int(data_splitted[0]) args_dict = {'c': str, 'H': int, 'f': float} - args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] + args = [args_dict[t](s) for t, s in itertools.izip(self.stm_protocol.pack_format[cmd][1:], data_splitted[1:])] return cmd, args if __name__ == '__main__': diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 83a3994..1bcc3c8 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -23,7 +23,11 @@ def __init__(self, serial_port, baudrate=115200): 0x11: "=", 0x12: "=", 0x13: "=", - 0x14: "=" + 0x14: "=", + 0x15: "=", + 0x16: "=", + 0x17: "=", + 0x18: "=" } self.unpack_format = { @@ -37,7 +41,11 @@ def __init__(self, serial_port, baudrate=115200): 0x11: "=cc", 0x12: "=cc", 0x13: "=cc", - 0x14: "=cc" + 0x14: "=cc", + 0x15: "=cc", + 0x16: "=cc", + 0x17: "=cc", + 0x18: "=cc" } self.response_bytes = { @@ -51,7 +59,11 @@ def __init__(self, serial_port, baudrate=115200): 0x11: 2, 0x12: 2, 0x13: 2, - 0x14: 2 + 0x14: 2, + 0x15: 2, + 0x16: 2, + 0x17: 2, + 0x18: 2 } def send(self, cmd, args): diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 4265cc3..57a7990 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -1 +1,41 @@ #!/usr/bin/env python +import rospy +from std_msgs.msg import String + +class Manipulator(): + def __init__(self): + self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) + self.collect_puck() + def collect_puck(self): + # Release grabber + print("__1__") + self.publisher.publish(String("22")) + # Set pump to the wall + self.publisher.publish(String("20")) + # Set pump to the ground + self.publisher.publish("19") + # Start pump + self.publisher.publish("17") + # Set pump to the platform + self.publisher.publish("21") + # Prop pack + self.publisher.publish("23") + # Stop pump + self.publisher.publish("18") + # Set pump to the wall + self.publisher.publish("20") + # Grab pack + self.publisher.publish("24") + # Release grabber + self.publisher.publish("22") + +if __name__=="__main__": + print("1") + rospy.init_node("manuipulator_node", anonymous=True) + manipulator = Manipulator() + manipulator.collect_puck() + rospy.spin() + print("2") + #manipulator.collect_puck() + + diff --git a/eurobot_stm/scripts/odometry.py b/eurobot_stm/scripts/odometry.py index 9bd19f2..a014d33 100755 --- a/eurobot_stm/scripts/odometry.py +++ b/eurobot_stm/scripts/odometry.py @@ -15,7 +15,7 @@ def __init__(self, stm_protocol, rate): def odom_callback(self, event): - self.stm_protocol.send(0x0F, args=None) + successfully, values = self.stm_protocol.send(0x0F, args=None) if successfully: self.send_odometry(values) From f066dfd5af8d9793cbc8b9d1aec1aa49ba17cc65 Mon Sep 17 00:00:00 2001 From: nickzherdev Date: Tue, 29 Jan 2019 19:00:42 +0300 Subject: [PATCH 11/40] changes after testing --- eurobot_stm/scripts/manipulator.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 57a7990..f168d4d 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -1,10 +1,12 @@ #!/usr/bin/env python +import time import rospy from std_msgs.msg import String class Manipulator(): def __init__(self): self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) + time.sleep(2) self.collect_puck() def collect_puck(self): # Release grabber From c693920ac08e5660978860816427bc55fb176802 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 6 Feb 2019 16:13:39 +0300 Subject: [PATCH 12/40] minor changes --- eurobot_stm/configs/stm.yaml | 1 + eurobot_stm/scripts/STM.py | 14 +++++----- eurobot_stm/scripts/STM_node.py | 40 +++++++++++++++++++++++++++++ eurobot_stm/scripts/STM_protocol.py | 2 +- eurobot_stm/scripts/manipulator.py | 5 ++++ eurobot_stm/scripts/odometry.py | 4 +-- 6 files changed, 56 insertions(+), 10 deletions(-) create mode 100644 eurobot_stm/configs/stm.yaml create mode 100644 eurobot_stm/scripts/STM_node.py diff --git a/eurobot_stm/configs/stm.yaml b/eurobot_stm/configs/stm.yaml new file mode 100644 index 0000000..11fed12 --- /dev/null +++ b/eurobot_stm/configs/stm.yaml @@ -0,0 +1 @@ +ODOM_RATE: 40 diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index e1ecce6..f82e1b5 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -5,10 +5,12 @@ import serial import itertools + from STM_protocol import STMprotocol -import odometry +from odometry import Odometry +from manipulator import Manipulator -ODOM_RATE = 40 # Hz +ODOM_RATE = rospy.get_param("ODOM_RATE") class STM(): def __init__(self, serial_port, baudrate=115200): @@ -17,11 +19,9 @@ def __init__(self, serial_port, baudrate=115200): # ROS subscribers rospy.Subscriber("stm_command", String, self.stm_command_callback) - self.stm_protocol = STMprotocol(serial_port, baudrate) - self.odometry = Odometry(self.stm_protocol, ODOM_RATE) - - self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) - self.laser_angle = rospy.get_param('lidar_a') + self.stm_protocol = STMprotocol(serial_port, baudrate) + self.odometry = Odometry(self.stm_protocol, ODOM_RATE) + self.manipulator = Manipulator() def stm_command_callback(self, data): cmd, args = self.parse_data(data) diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py new file mode 100644 index 0000000..e1ecce6 --- /dev/null +++ b/eurobot_stm/scripts/STM_node.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python +import rospy +from std_msgs.msg import String +from threading import Lock + +import serial +import itertools +from STM_protocol import STMprotocol +import odometry + +ODOM_RATE = 40 # Hz + +class STM(): + def __init__(self, serial_port, baudrate=115200): + # Init ROS + rospy.init_node('stm_node', anonymous=True) + # ROS subscribers + rospy.Subscriber("stm_command", String, self.stm_command_callback) + + self.stm_protocol = STMprotocol(serial_port, baudrate) + self.odometry = Odometry(self.stm_protocol, ODOM_RATE) + + self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) + self.laser_angle = rospy.get_param('lidar_a') + + def stm_command_callback(self, data): + cmd, args = self.parse_data(data) + successfully, values = self.stm_protocol.send(cmd, args) + + def parse_data(self, data): + data_splitted = data.data.split() + cmd = int(data_splitted[0]) + args_dict = {'c': str, 'H': int, 'f': float} + args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] + return cmd, args + +if __name__ == '__main__': + serial_port = "/dev/ttyUSB0" + stm = STM(serial_port) + rospy.spin() diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index f565177..ced6c89 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -71,7 +71,7 @@ def pure_send_command(self, cmd, args): msg += parameters self.ser.write(msg) response = self.ser.read(self.response_bytes[cmd]+1) - print response + print (response) if len(response) == 0: raise Exception("No data received") values = struct.unpack(self.unpack_format[cmd], response) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 4265cc3..50ff714 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -1 +1,6 @@ #!/usr/bin/env python + + + +class Manipulator(): + def __init__(self): diff --git a/eurobot_stm/scripts/odometry.py b/eurobot_stm/scripts/odometry.py index de75c26..882b051 100755 --- a/eurobot_stm/scripts/odometry.py +++ b/eurobot_stm/scripts/odometry.py @@ -7,7 +7,7 @@ class Odometry(): - def __init__(self, rate=40, stm_protocol): + def __init__(self, stm_protocol, rate=40): self.tf2_broad = tf2_ros.TransformBroadcaster() self.stm_protocol = stm_protocol @@ -15,7 +15,7 @@ def __init__(self, rate=40, stm_protocol): def odom_callback(self, event): - self.stm_protocol.send(0x0F, args=None) + successfully, values = self.stm_protocol.send(0x0F, args=None) if successfully: self.send_odometry(values) From b0400c1949081bc724f4234c0f7563964552b512 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 6 Feb 2019 17:25:28 +0300 Subject: [PATCH 13/40] add response publisher --- eurobot_stm/scripts/STM.py | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index f82e1b5..5514503 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -1,9 +1,7 @@ #!/usr/bin/env python import rospy from std_msgs.msg import String -from threading import Lock -import serial import itertools from STM_protocol import STMprotocol @@ -14,18 +12,18 @@ class STM(): def __init__(self, serial_port, baudrate=115200): - # Init ROS rospy.init_node('stm_node', anonymous=True) - # ROS subscribers - rospy.Subscriber("stm_command", String, self.stm_command_callback) + rospy.Subscriber("stm_command", String, self.stm_command_callback) + self.response = rospy.Publisher("stm_response", String, queue_size=50) self.stm_protocol = STMprotocol(serial_port, baudrate) self.odometry = Odometry(self.stm_protocol, ODOM_RATE) - self.manipulator = Manipulator() def stm_command_callback(self, data): - cmd, args = self.parse_data(data) + id, cmd, args = self.parse_data(data) successfully, values = self.stm_protocol.send(cmd, args) + response = str(id) + " " + str(values) + self.response.publish(response) def parse_data(self, data): data_splitted = data.data.split() @@ -37,4 +35,4 @@ def parse_data(self, data): if __name__ == '__main__': serial_port = "/dev/ttyUSB0" stm = STM(serial_port) - rospy.spin() + rospy.spin() \ No newline at end of file From e74944e0c6e9ce8586b0b843a59d0172b70f4b3a Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 6 Feb 2019 17:47:52 +0300 Subject: [PATCH 14/40] minor changes --- eurobot_stm/scripts/STM.py | 5 +++-- eurobot_stm/scripts/STM_protocol.py | 2 +- eurobot_stm/scripts/manipulator.py | 20 ++++++++++---------- eurobot_stm/scripts/odometry.py | 1 - 4 files changed, 14 insertions(+), 14 deletions(-) diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index 8e0bdff..d8a383e 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -28,10 +28,11 @@ def stm_command_callback(self, data): def parse_data(self, data): data_splitted = data.data.split() - cmd = int(data_splitted[0]) + id = data_splitted[0] + cmd = int(data_splitted[1]) args_dict = {'c': str, 'H': int, 'f': float} args = [args_dict[t](s) for t, s in itertools.izip(self.stm_protocol.pack_format[cmd][1:], data_splitted[1:])] - return cmd, args + return id, cmd, args if __name__ == '__main__': serial_port = "/dev/ttyUSB0" diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 671193c..c6863c4 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -28,7 +28,7 @@ def __init__(self, serial_port, baudrate=115200): 0x17: "=", 0x18: "=", 0x20: "=", - 0x21: "=", + 0x21: "=I", 0x22: "=", 0x23: "=", } diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 920487c..f4c9b22 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -12,25 +12,25 @@ def __init__(self): def collect_puck(self): # Release grabber print("__1__") - self.publisher.publish(String("22")) + self.publisher.publish(String("manipulator-1 22")) # Set pump to the wall - self.publisher.publish(String("20")) + self.publisher.publish(String("manipulator-2 20")) # Set pump to the ground - self.publisher.publish("19") + self.publisher.publish("manipulator-3 19") # Start pump - self.publisher.publish("17") + self.publisher.publish("manipulator-4 17") # Set pump to the platform - self.publisher.publish("21") + self.publisher.publish("manipulator-5 21") # Prop pack - self.publisher.publish("23") + self.publisher.publish("manipulator-6 23") # Stop pump - self.publisher.publish("18") + self.publisher.publish("manipulator-7 18") # Set pump to the wall - self.publisher.publish("20") + self.publisher.publish("manipulator-8 20") # Grab pack - self.publisher.publish("24") + self.publisher.publish("manipulator-9 24") # Release grabber - self.publisher.publish("22") + self.publisher.publish("manipulator-10 22") if __name__=="__main__": print("1") diff --git a/eurobot_stm/scripts/odometry.py b/eurobot_stm/scripts/odometry.py index 69a1b63..0e6d631 100755 --- a/eurobot_stm/scripts/odometry.py +++ b/eurobot_stm/scripts/odometry.py @@ -3,7 +3,6 @@ import geometry_msgs.msg import tf_conversions import tf2_ros -import STM_protocol class Odometry(): From 0ac66b8d420ac5b3338d0b777f935e4cac33d93a Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 6 Feb 2019 18:57:06 +0300 Subject: [PATCH 15/40] add resposne for manipulator --- eurobot_stm/scripts/manipulator.py | 58 ++++++++++++++++++++++-------- 1 file changed, 44 insertions(+), 14 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index f4c9b22..e672acb 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -1,36 +1,67 @@ #!/usr/bin/env python import time +import re + import rospy from std_msgs.msg import String class Manipulator(): - def __init__(self): - self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) - time.sleep(2) + def __init__(self): + self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) + rospy.Subscriber("/seondary_robot/stm_response", String, self.response_callback) + self.las_response_id = None + self.last_response_args = None + time.sleep(2) + + def response_callback(self, data): + response = data.split() + if re.match(r"manipulator-*", response[0]): + self.las_response_id = response[0] + self.last_response_args = response[1] + + def send_command(self, id, cmd): + self.publisher.publish(String("manipulator-" + str(id) + " " + str(cmd))) + while(True): + if self.last_response_id == id: + return self.last_response_args + + + + def collect_puck(self): # Release grabber print("__1__") - self.publisher.publish(String("manipulator-1 22")) + self.send_command(1, 22) + # self.publisher.publish(String("manipulator-1 22")) # Set pump to the wall - self.publisher.publish(String("manipulator-2 20")) + self.send_command(2, 20) + # self.publisher.publish(String("manipulator-2 20")) # Set pump to the ground - self.publisher.publish("manipulator-3 19") + self.send_command(3, 19) + # self.publisher.publish("manipulator-3 19") # Start pump - self.publisher.publish("manipulator-4 17") + self.send_command(4, 17) + # self.publisher.publish("manipulator-4 17") # Set pump to the platform - self.publisher.publish("manipulator-5 21") + self.send_command(5, 21) + # self.publisher.publish("manipulator-5 21") # Prop pack - self.publisher.publish("manipulator-6 23") + self.send_command(6, 23) + # self.publisher.publish("manipulator-6 23") # Stop pump - self.publisher.publish("manipulator-7 18") + self.send_command(7, 18) + # self.publisher.publish("manipulator-7 18") # Set pump to the wall - self.publisher.publish("manipulator-8 20") + self.send_command(8, 20) + # self.publisher.publish("manipulator-8 20") # Grab pack - self.publisher.publish("manipulator-9 24") + self.send_command(9, 24) + # self.publisher.publish("manipulator-9 24") # Release grabber - self.publisher.publish("manipulator-10 22") + self.send_command(10, 22) + # self.publisher.publish("manipulator-10 22") if __name__=="__main__": print("1") @@ -38,4 +69,3 @@ def collect_puck(self): manipulator = Manipulator() manipulator.collect_puck() print("2") - #manipulator.collect_puck() From 91a946e0992e1bdd375253c61c2db9844c4b054e Mon Sep 17 00:00:00 2001 From: nickzherdev Date: Wed, 6 Feb 2019 18:59:02 +0300 Subject: [PATCH 16/40] add new commands. add config yaml to launch file --- eurobot_stm/launch/STM_node.launch | 2 ++ eurobot_stm/scripts/STM_protocol.py | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/eurobot_stm/launch/STM_node.launch b/eurobot_stm/launch/STM_node.launch index ac18e82..80a1325 100644 --- a/eurobot_stm/launch/STM_node.launch +++ b/eurobot_stm/launch/STM_node.launch @@ -1,5 +1,7 @@ + + diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index c6863c4..85eb3f3 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -48,7 +48,7 @@ def __init__(self, serial_port, baudrate=115200): 0x15: "=cc", 0x16: "=cc", 0x17: "=cc", - 0x18: "=cc" + 0x18: "=cc", 0x20: "=cc", 0x21: "=cc", 0x22: "=cc", From 7b74276f42524df99bc4b6942c95e1462cf8c93a Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 6 Feb 2019 19:01:52 +0300 Subject: [PATCH 17/40] add rosparam to launch file --- eurobot_stm/launch/STM_node.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/eurobot_stm/launch/STM_node.launch b/eurobot_stm/launch/STM_node.launch index ac18e82..d0e3213 100644 --- a/eurobot_stm/launch/STM_node.launch +++ b/eurobot_stm/launch/STM_node.launch @@ -1,5 +1,6 @@ + From 66de0fa64d667d12ba3efb0b32e526135fbbf56e Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Sun, 10 Feb 2019 14:25:20 +0300 Subject: [PATCH 18/40] add working manipulator --- eurobot_stm/scripts/STM_node.py | 40 ------------- eurobot_stm/scripts/manipulator.py | 95 ++++++++++++++++++------------ 2 files changed, 56 insertions(+), 79 deletions(-) delete mode 100644 eurobot_stm/scripts/STM_node.py diff --git a/eurobot_stm/scripts/STM_node.py b/eurobot_stm/scripts/STM_node.py deleted file mode 100644 index e1ecce6..0000000 --- a/eurobot_stm/scripts/STM_node.py +++ /dev/null @@ -1,40 +0,0 @@ -#!/usr/bin/env python -import rospy -from std_msgs.msg import String -from threading import Lock - -import serial -import itertools -from STM_protocol import STMprotocol -import odometry - -ODOM_RATE = 40 # Hz - -class STM(): - def __init__(self, serial_port, baudrate=115200): - # Init ROS - rospy.init_node('stm_node', anonymous=True) - # ROS subscribers - rospy.Subscriber("stm_command", String, self.stm_command_callback) - - self.stm_protocol = STMprotocol(serial_port, baudrate) - self.odometry = Odometry(self.stm_protocol, ODOM_RATE) - - self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) - self.laser_angle = rospy.get_param('lidar_a') - - def stm_command_callback(self, data): - cmd, args = self.parse_data(data) - successfully, values = self.stm_protocol.send(cmd, args) - - def parse_data(self, data): - data_splitted = data.data.split() - cmd = int(data_splitted[0]) - args_dict = {'c': str, 'H': int, 'f': float} - args = [args_dict[t](s) for t, s in itertools.izip(self.pack_format[cmd][1:], data_splitted[1:])] - return cmd, args - -if __name__ == '__main__': - serial_port = "/dev/ttyUSB0" - stm = STM(serial_port) - rospy.spin() diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index e672acb..6d19217 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -9,63 +9,80 @@ class Manipulator(): def __init__(self): + rospy.init_node("manuipulator_node", anonymous=True) + self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) - rospy.Subscriber("/seondary_robot/stm_response", String, self.response_callback) - self.las_response_id = None + rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) + self.last_response_id = None self.last_response_args = None - time.sleep(2) + rospy.sleep(2) def response_callback(self, data): - response = data.split() - if re.match(r"manipulator-*", response[0]): - self.las_response_id = response[0] + response = data.data.split() + if re.match(r"manipulator-\d", response[0]): + print ("response[0]", response[0]) + self.last_response_id = response[0] self.last_response_args = response[1] def send_command(self, id, cmd): - self.publisher.publish(String("manipulator-" + str(id) + " " + str(cmd))) - while(True): - if self.last_response_id == id: - return self.last_response_args - - + while (True): + self.publisher.publish(String("manipulator-" + str(id) + " " + str(cmd))) + print ("last_response_id=",self.last_response_id) + print("laste_response_args", self.last_response_args) + rospy.sleep(0.1) + if self.last_response_id == ("manipulator-"+str(id)): + print ("YYYYYEEEESSSS") + if self.last_response_args == "OK": + print("AS Date: Sun, 10 Feb 2019 19:44:08 +0300 Subject: [PATCH 19/40] minor changes --- eurobot_stm/scripts/manipulator.py | 63 +++++++++++------------------- 1 file changed, 23 insertions(+), 40 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index a69163e..467a263 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -1,5 +1,4 @@ #!/usr/bin/env python -import time import re import rospy @@ -15,75 +14,59 @@ def __init__(self): rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) self.last_response_id = None self.last_response_args = None + self.id_command = 0 rospy.sleep(2) def response_callback(self, data): response = data.data.split() if re.match(r"manipulator-\d", response[0]): - print ("response[0]", response[0]) - self.last_response_id = response[0] - self.last_response_id = response[0] + self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, id, cmd): + def send_command(self, cmd): while (True): - self.publisher.publish(String("manipulator-" + str(id) + " " + str(cmd))) - print ("last_response_id=",self.last_response_id) - print("laste_response_args", self.last_response_args) + self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd))) + self.id_command += 1 rospy.sleep(0.1) - if self.last_response_id == ("manipulator-"+str(id)): - print ("YYYYYEEEESSSS") + if self.last_response_id == (str(id)): if self.last_response_args == "OK": + return self.last_response_args + # if don't get response a lot of time + + + + def calibrate_step_motor(self): + self.send_command("manipulator-calibrate_step_motor", 32) def collect_puck(self): # Release grabber - print("__1__") - self.send_command(1, 22) + self.send_command("manipulator-release_grabber", 22) rospy.sleep(0.5) - # self.publisher.publish(String("manipulator-1 22")) # Set pump to the wall - self.send_command(2, 20) + self.send_command("manipulator-set_pump_to_the_wall", 20) rospy.sleep(0.5) - - # self.publisher.publish(String("manipulator-2 20")) # Set pump to the ground - self.send_command(3, 19) + self.send_command("manipulator-set_pump_to_the_ground", 19) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-3 19") # Start pump - self.send_command(4, 17) + self.send_command("manipulator-start_pump", 17) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-4 17") # Set pump to the platform - self.send_command(5, 21) + self.send_command("manipulator-set_pump_to_the_platform", 21) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-5 21") # Prop pack - self.send_command(6, 23) + self.send_command("manipulator-prop_pack", 23) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-6 23") # Stop pump - self.send_command(7, 18) + self.send_command("manipulator-stop_pump", 18) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-7 18") # Set pump to the wall - self.send_command(8, 20) + self.send_command("manipulator-set_pump_to_the_wall", 20) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-8 20") # Grab pack - self.send_command(9, 24) + self.send_command("manipulator-grab_pack", 24) rospy.sleep(0.5) - - # self.publisher.publish("manipulator-9 24") # Release grabber - self.send_command(10, 22) - # self.publisher.publish("manipulator-10 22") - + self.send_command("manipulator-release_grabber", 22) From be283c2afa8e009199a9c8f8bc502f8e8266a657 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 16:29:11 +0300 Subject: [PATCH 20/40] add new commands --- eurobot_stm/scripts/STM_protocol.py | 24 ++++++++++++++++++++---- 1 file changed, 20 insertions(+), 4 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 88a8f7d..b9a7008 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -27,10 +27,15 @@ def __init__(self, serial_port, baudrate=115200): 0x16: "=", 0x17: "=", 0x18: "=", + 0x19: "=", 0x20: "=", - 0x21: "=I", + 0x21: "=B", 0x22: "=", 0x23: "=", + 0x30: "=B", + 0x31: "=", + 0x32: "=B", + 0x33: "=B", } self.unpack_format = { @@ -49,12 +54,18 @@ def __init__(self, serial_port, baudrate=115200): 0x16: "=cc", 0x17: "=cc", 0x18: "=cc", + 0x19: "=cc", 0x20: "=cc", 0x21: "=cc", 0x22: "=cc", 0x23: "=cc", + 0x30: "=cc", + 0x31: "=cc", + 0x32: "=cc", + 0x33: "=cc", + } - + self.response_bytes = { 0x01: 4, 0x07: 12, @@ -71,10 +82,15 @@ def __init__(self, serial_port, baudrate=115200): 0x16: 2, 0x17: 2, 0x18: 2, + 0x19: 2, 0x20: 2, 0x21: 2, 0x22: 2, 0x23: 2, + 0x30: 2, + 0x31: 2, + 0x32: 2, + 0x33: 2, } def send(self, cmd, args): @@ -101,8 +117,8 @@ def pure_send_command(self, cmd, args): raise Exception("No data received") values = struct.unpack(self.unpack_format[cmd], response) return True, values - - + + def send_command(self, cmd, args, n_repeats=5): for i in range(n_repeats): try: From 6a7e8d4ec1698571370b9484935f69ea6315e2b5 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 17:48:31 +0300 Subject: [PATCH 21/40] fix bugs, add hex cmd format --- eurobot_stm/scripts/STM.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index fa502a3..eac6051 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -30,10 +30,14 @@ def stm_command_callback(self, data): def parse_data(self, data): data_splitted = data.data.split() + print (data_splitted) id = data_splitted[0] - cmd = int(data_splitted[1]) - args_dict = {'c': str, 'H': int, 'f': float} - args = [args_dict[t](s) for t, s in itertools.izip(self.stm_protocol.pack_format[cmd][1:], data_splitted[1:])] + try: + cmd = int(data_splitted[1]) + except ValueError as e: + cmd = int(data_splitted[1], 16) + args_dict = {'c': str, 'B': int, 'f': float} + args = [args_dict[t](s) for t, s in itertools.izip(self.stm_protocol.pack_format[cmd][1:], data_splitted[2:])] return id, cmd, args if __name__ == '__main__': From b93a7456294393e6ab7417811211c01894346148 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 18:15:13 +0300 Subject: [PATCH 22/40] add calibrate for big robot --- eurobot_stm/scripts/manipulator.py | 34 +++++++++++++++++++----------- 1 file changed, 22 insertions(+), 12 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 467a263..451d971 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -23,9 +23,9 @@ def response_callback(self, data): self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, cmd): + def send_command(self, cmd, args): while (True): - self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd))) + self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd) + str(args))) self.id_command += 1 rospy.sleep(0.1) if self.last_response_id == (str(id)): @@ -37,36 +37,46 @@ def send_command(self, cmd): def calibrate_step_motor(self): - self.send_command("manipulator-calibrate_step_motor", 32) +# 1) collector move left +# 2) start calibration right stepper +# 3) make step down by right stepper +# 4) collector move right +# 5) start calibration left stepper +# 6) make step down by left stepper +# 7) make step down by left stepper +# 9) collector move default + self.send_command("manipulator-calibrate_step_motor_1", 33) + self.send_command("manipulator-calibrate_step_motor_2", 48, 1) + + self.send_command("manipulator-calibrate_step_motor_3", 50, 1) + self.send_command("manipulator-calibrate_step_motor_4", 32) + + self.send_command("manipulator-calibrate_step_motor_5", 48, 0) + self.send_command("manipulator-calibrate_step_motor_6", 50, 0) + + + self.send_command("manipulator-calibrate_step_motor_7", 50, 0) + self.send_command("manipulator-calibrate_step_motor_8", 25) def collect_puck(self): # Release grabber self.send_command("manipulator-release_grabber", 22) - rospy.sleep(0.5) # Set pump to the wall self.send_command("manipulator-set_pump_to_the_wall", 20) - rospy.sleep(0.5) # Set pump to the ground self.send_command("manipulator-set_pump_to_the_ground", 19) - rospy.sleep(0.5) # Start pump self.send_command("manipulator-start_pump", 17) - rospy.sleep(0.5) # Set pump to the platform self.send_command("manipulator-set_pump_to_the_platform", 21) - rospy.sleep(0.5) # Prop pack self.send_command("manipulator-prop_pack", 23) - rospy.sleep(0.5) # Stop pump self.send_command("manipulator-stop_pump", 18) - rospy.sleep(0.5) # Set pump to the wall self.send_command("manipulator-set_pump_to_the_wall", 20) - rospy.sleep(0.5) # Grab pack self.send_command("manipulator-grab_pack", 24) - rospy.sleep(0.5) # Release grabber self.send_command("manipulator-release_grabber", 22) From 165e50aaee842d93d375467accb8867583fd2a68 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 18:15:20 +0300 Subject: [PATCH 23/40] add calibrate for big robot --- eurobot_stm/scripts/manipulator.py | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 451d971..0a8a4df 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -35,16 +35,18 @@ def send_command(self, cmd, args): # if don't get response a lot of time - - def calibrate_step_motor(self): -# 1) collector move left -# 2) start calibration right stepper -# 3) make step down by right stepper -# 4) collector move right -# 5) start calibration left stepper -# 6) make step down by left stepper -# 7) make step down by left stepper -# 9) collector move default + def calibrate_small_robot(self): + self.send_command("manipulator-calibrate_step_motor_1", 48) + + def calibrate_big_robot(self): + # 1) collector move left + # 2) start calibration right stepper + # 3) make step down by right stepper + # 4) collector move right + # 5) start calibration left stepper + # 6) make step down by left stepper + # 7) make step down by left stepper + # 9) collector move default self.send_command("manipulator-calibrate_step_motor_1", 33) self.send_command("manipulator-calibrate_step_motor_2", 48, 1) From 7a91fe74a0b41ee20df04c6b956ac5ea351c0fda Mon Sep 17 00:00:00 2001 From: nickzherdev Date: Wed, 20 Feb 2019 18:26:16 +0300 Subject: [PATCH 24/40] fix bugs --- eurobot_stm/scripts/manipulator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 0a8a4df..a2bc0a8 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -23,9 +23,9 @@ def response_callback(self, data): self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, cmd, args): + def send_command(self, id, cmd, args): while (True): - self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd) + str(args))) + self.publisher.publish(String(str(id) +str(cmd) + str(args))) self.id_command += 1 rospy.sleep(0.1) if self.last_response_id == (str(id)): From 2861899c65c362863f5e57cbfe227e424a61c77f Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 18:26:57 +0300 Subject: [PATCH 25/40] fix bugs --- eurobot_stm/scripts/manipulator.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 0a8a4df..3bc73d7 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -23,9 +23,14 @@ def response_callback(self, data): self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, cmd, args): + def send_command(self, id, cmd, args=None): + message = "" + if args == None: + message = str(id) +str(cmd) + else: + message = str(id) + str(cmd) + str(args) while (True): - self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd) + str(args))) + self.publisher.publish(String(message)) self.id_command += 1 rospy.sleep(0.1) if self.last_response_id == (str(id)): From bb9c2feef02e4c8be8df0a3c7135719f8c615e3a Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 18:37:56 +0300 Subject: [PATCH 26/40] manipulator fix bugs --- eurobot_stm/scripts/manipulator.py | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 3bc73d7..eb78143 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -14,7 +14,7 @@ def __init__(self): rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) self.last_response_id = None self.last_response_args = None - self.id_command = 0 + self.id_command = 1 rospy.sleep(2) def response_callback(self, data): @@ -23,19 +23,18 @@ def response_callback(self, data): self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, id, cmd, args=None): + def send_command(self, cmd, args=None): message = "" if args == None: - message = str(id) +str(cmd) + message = str(self.id_command) + str(cmd) else: - message = str(id) + str(cmd) + str(args) + message = str(self.id_command) + str(cmd) + str(args) while (True): self.publisher.publish(String(message)) self.id_command += 1 rospy.sleep(0.1) - if self.last_response_id == (str(id)): + if self.last_response_id == (str(self.id_command)): if self.last_response_args == "OK": - return self.last_response_args # if don't get response a lot of time @@ -52,18 +51,18 @@ def calibrate_big_robot(self): # 6) make step down by left stepper # 7) make step down by left stepper # 9) collector move default - self.send_command("manipulator-calibrate_step_motor_1", 33) - self.send_command("manipulator-calibrate_step_motor_2", 48, 1) + self.send_command(33) + self.send_command(48, 1) - self.send_command("manipulator-calibrate_step_motor_3", 50, 1) - self.send_command("manipulator-calibrate_step_motor_4", 32) + self.send_command(50, 1) + self.send_command(32) - self.send_command("manipulator-calibrate_step_motor_5", 48, 0) - self.send_command("manipulator-calibrate_step_motor_6", 50, 0) + self.send_command(48, 0) + self.send_command(50, 0) - self.send_command("manipulator-calibrate_step_motor_7", 50, 0) - self.send_command("manipulator-calibrate_step_motor_8", 25) + self.send_command(50, 0) + self.send_command(25) def collect_puck(self): From db42b471a50496e2a21c6f7c6b86d93bbd68c53a Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 18:37:56 +0300 Subject: [PATCH 27/40] manipulator fix bugs --- eurobot_stm/scripts/manipulator.py | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 3bc73d7..175be3c 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -14,7 +14,7 @@ def __init__(self): rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) self.last_response_id = None self.last_response_args = None - self.id_command = 0 + self.id_command = 1 rospy.sleep(2) def response_callback(self, data): @@ -23,14 +23,14 @@ def response_callback(self, data): self.last_response_id = response[0] self.last_response_args = response[1] - def send_command(self, id, cmd, args=None): + def send_command(self, cmd, args=None): message = "" if args == None: - message = str(id) +str(cmd) + message = str(self.id_command) + str(cmd) else: - message = str(id) + str(cmd) + str(args) + message = str(self.id_command) + str(cmd) + str(args) while (True): - self.publisher.publish(String(message)) + self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd))) self.id_command += 1 rospy.sleep(0.1) if self.last_response_id == (str(id)): @@ -52,18 +52,18 @@ def calibrate_big_robot(self): # 6) make step down by left stepper # 7) make step down by left stepper # 9) collector move default - self.send_command("manipulator-calibrate_step_motor_1", 33) - self.send_command("manipulator-calibrate_step_motor_2", 48, 1) + self.send_command(33) + self.send_command(48, 1) - self.send_command("manipulator-calibrate_step_motor_3", 50, 1) - self.send_command("manipulator-calibrate_step_motor_4", 32) + self.send_command(50, 1) + self.send_command(32) - self.send_command("manipulator-calibrate_step_motor_5", 48, 0) - self.send_command("manipulator-calibrate_step_motor_6", 50, 0) + self.send_command(48, 0) + self.send_command(50, 0) - self.send_command("manipulator-calibrate_step_motor_7", 50, 0) - self.send_command("manipulator-calibrate_step_motor_8", 25) + self.send_command(50, 0) + self.send_command(25) def collect_puck(self): From 835e5e3a4a8628c9cb52af67b55018cf607cedb3 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 19:34:32 +0300 Subject: [PATCH 28/40] add collect puck for big robot --- eurobot_stm/scripts/manipulator.py | 61 +++++++++++++++++++++++------- 1 file changed, 47 insertions(+), 14 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 00d3d42..aac3994 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -26,15 +26,16 @@ def response_callback(self, data): def send_command(self, cmd, args=None): message = "" if args == None: - message = str(self.id_command) + str(cmd) + message = "manipulator-" + str(self.id_command) + " " + str(cmd) else: - message = str(self.id_command) + str(cmd) + str(args) + message = "manipulator-" + str(self.id_command) + " " + str(cmd) + " " + str(args) while (True): - self.publisher.publish(String("manipulator-"+self.id_command+" "+str(cmd))) - self.id_command += 1 + self.publisher.publish(String(message)) + rospy.sleep(0.1) if self.last_response_id == (str(self.id_command)): if self.last_response_args == "OK": + self.id_command += 1 return self.last_response_args # if don't get response a lot of time @@ -55,6 +56,7 @@ def calibrate_big_robot(self): self.send_command(48, 1) self.send_command(50, 1) + rospy.sleep(2) self.send_command(32) self.send_command(48, 0) @@ -65,24 +67,55 @@ def calibrate_big_robot(self): self.send_command(25) + def collect_puck_big(self): + # Release grabber + self.send_command(22) + # Collector move default + self.send_command(25) + # Set pump to the wall + self.send_command(20) + # Set pump to the ground + self.send_command(19) + # Start pump + self.send_command(17) + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # Grab pack + self.send_command(24) + # Collector move right/left + self.send_command(32) + # Make step down left / right collector + self.send_command(50, 1) + # Release grabber + self.send_command(22) + + + + def collect_puck(self): # Release grabber - self.send_command("manipulator-release_grabber", 22) + self.send_command(22) # Set pump to the wall - self.send_command("manipulator-set_pump_to_the_wall", 20) + self.send_command(20) # Set pump to the ground - self.send_command("manipulator-set_pump_to_the_ground", 19) + self.send_command(19) # Start pump - self.send_command("manipulator-start_pump", 17) + self.send_command(17) # Set pump to the platform - self.send_command("manipulator-set_pump_to_the_platform", 21) + self.send_command(21) # Prop pack - self.send_command("manipulator-prop_pack", 23) + self.send_command(23) # Stop pump - self.send_command("manipulator-stop_pump", 18) + self.send_command(18) # Set pump to the wall - self.send_command("manipulator-set_pump_to_the_wall", 20) + self.send_command(20) # Grab pack - self.send_command("manipulator-grab_pack", 24) + self.send_command(24) # Release grabber - self.send_command("manipulator-release_grabber", 22) + self.send_command(22) From 78715ef6920534322ee70f5490c7a50251e389ff Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Wed, 20 Feb 2019 20:21:40 +0300 Subject: [PATCH 29/40] add releaser --- eurobot_stm/scripts/manipulator.py | 30 +++++++++++++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index aac3994..5f41e5d 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -33,7 +33,7 @@ def send_command(self, cmd, args=None): self.publisher.publish(String(message)) rospy.sleep(0.1) - if self.last_response_id == (str(self.id_command)): + if self.last_response_id == ("manipulator-" + str(self.id_command)): if self.last_response_args == "OK": self.id_command += 1 return self.last_response_args @@ -70,31 +70,59 @@ def calibrate_big_robot(self): def collect_puck_big(self): # Release grabber self.send_command(22) + rospy.sleep(0.5) # Collector move default self.send_command(25) + rospy.sleep(0.5) # Set pump to the wall self.send_command(20) + rospy.sleep(0.5) # Set pump to the ground self.send_command(19) + rospy.sleep(0.5) # Start pump self.send_command(17) + rospy.sleep(0.5) # Set pump to the platform self.send_command(21) + rospy.sleep(0.5) # Prop pack self.send_command(23) + rospy.sleep(0.5) # Stop pump self.send_command(18) + rospy.sleep(0.5) # Set pump to the wall self.send_command(20) + rospy.sleep(0.5) # Grab pack self.send_command(24) + rospy.sleep(0.5) # Collector move right/left self.send_command(32) + rospy.sleep(0.5) # Make step down left / right collector self.send_command(50, 1) + rospy.sleep(0.5) # Release grabber self.send_command(22) + def release_puck(self): + # Release grabber + self.send_command(33) + rospy.sleep(0.5) + # Collector move default + self.send_command(34) + rospy.sleep(0.5) + # Set pump to the wall + self.send_command(51, 1) + rospy.sleep(0.5) + # Release grabber + self.send_command(51, 1) + rospy.sleep(0.5) + # Collector move default + self.send_command(35) + rospy.sleep(0.5) From 37b5663ef46989a0270b710d2508471590c28024 Mon Sep 17 00:00:00 2001 From: nickzherdev Date: Thu, 21 Feb 2019 15:59:00 +0300 Subject: [PATCH 30/40] after big robot tests --- eurobot_stm/scripts/STM_protocol.py | 4 ++- eurobot_stm/scripts/manipulator.py | 40 ++++++++++++++++++++++++----- 2 files changed, 37 insertions(+), 7 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index b9a7008..53ffc51 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -36,6 +36,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=", 0x32: "=B", 0x33: "=B", + 0x34: "=B" } self.unpack_format = { @@ -63,7 +64,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=cc", 0x32: "=cc", 0x33: "=cc", - + 0x34: "=cc" } self.response_bytes = { @@ -91,6 +92,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: 2, 0x32: 2, 0x33: 2, + 0x34: 2 } def send(self, cmd, args): diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index aac3994..66547f3 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -19,7 +19,8 @@ def __init__(self): def response_callback(self, data): response = data.data.split() - if re.match(r"manipulator-\d", response[0]): + print ("RESPONSE=", response) + if re.match(r"manipulator-\d", response[0]): self.last_response_id = response[0] self.last_response_args = response[1] @@ -33,7 +34,7 @@ def send_command(self, cmd, args=None): self.publisher.publish(String(message)) rospy.sleep(0.1) - if self.last_response_id == (str(self.id_command)): + if self.last_response_id == ("manipulator-" + str(self.id_command)): if self.last_response_args == "OK": self.id_command += 1 return self.last_response_args @@ -56,7 +57,8 @@ def calibrate_big_robot(self): self.send_command(48, 1) self.send_command(50, 1) - rospy.sleep(2) + self.send_command(52, 1) + #rospy.sleep(3) self.send_command(32) self.send_command(48, 0) @@ -64,41 +66,67 @@ def calibrate_big_robot(self): self.send_command(50, 0) - self.send_command(25) + self.send_command(52, 0) + self.send_command(25) def collect_puck_big(self): # Release grabber self.send_command(22) + #rospy.sleep(0.5) # Collector move default self.send_command(25) + #rospy.sleep(0.5) # Set pump to the wall self.send_command(20) + #rospy.sleep(0.5) # Set pump to the ground self.send_command(19) + #rospy.sleep(0.5) # Start pump self.send_command(17) + #rospy.sleep(0.5) # Set pump to the platform self.send_command(21) + #rospy.sleep(0.5) # Prop pack self.send_command(23) - # Stop pump + #rospy.sleep(0.5) + # Stop pump self.send_command(18) + #rospy.sleep(0.5) # Set pump to the wall self.send_command(20) + #rospy.sleep(0.5) # Grab pack self.send_command(24) + #rospy.sleep(0.5) # Collector move right/left self.send_command(32) + #rospy.sleep(0.5) # Make step down left / right collector self.send_command(50, 1) + #rospy.sleep(0.5) # Release grabber self.send_command(22) - def collect_puck(self): + def release_puck(self): + self.send_command(33) + #rospy.sleep(0.5) + self.send_command(34) + #rospy.sleep(0.5) + self.send_command(51, 1) + #rospy.sleep(0.5) + self.send_command(51, 1) + #rospy.sleep(0.5) + self.send_command(52, 1) + self.send_command(35) + #rospy.sleep(0.5) + + def collect_puck(self): # Release grabber self.send_command(22) # Set pump to the wall From a5a725b18f58a666a003c7659594d05ba8170392 Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Thu, 21 Feb 2019 16:28:12 +0300 Subject: [PATCH 31/40] add tests --- eurobot_stm/scripts/STM.py | 2 + eurobot_stm/scripts/STM_protocol.py | 6 +-- eurobot_stm/scripts/manipulator.py | 58 ++++-------------------- eurobot_stm/scripts/tests/calibration.py | 4 ++ eurobot_stm/scripts/tests/collect.py | 4 ++ eurobot_stm/scripts/tests/release.py | 3 ++ 6 files changed, 25 insertions(+), 52 deletions(-) create mode 100644 eurobot_stm/scripts/tests/calibration.py create mode 100644 eurobot_stm/scripts/tests/collect.py create mode 100644 eurobot_stm/scripts/tests/release.py diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index eac6051..9043fc4 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -41,6 +41,8 @@ def parse_data(self, data): return id, cmd, args if __name__ == '__main__': + #TODO::search for ports + serial_port = "/dev/ttyUSB0" stm = STM(serial_port) rospy.spin() diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 53ffc51..b8f40fa 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -36,7 +36,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=", 0x32: "=B", 0x33: "=B", - 0x34: "=B" + 0x34: "=B" } self.unpack_format = { @@ -64,7 +64,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=cc", 0x32: "=cc", 0x33: "=cc", - 0x34: "=cc" + 0x34: "=cc" } self.response_bytes = { @@ -92,7 +92,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: 2, 0x32: 2, 0x33: 2, - 0x34: 2 + 0x34: 2 } def send(self, cmd, args): diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 1705972..25bf561 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -5,10 +5,9 @@ from std_msgs.msg import String - class Manipulator(): def __init__(self): - rospy.init_node("manuipulator_node", anonymous=True) + # rospy.init_node("manuipulator_node", anonymous=True) self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) @@ -20,12 +19,11 @@ def __init__(self): def response_callback(self, data): response = data.data.split() print ("RESPONSE=", response) - if re.match(r"manipulator-\d", response[0]): + if re.match(r"manipulator-\d", response[0]): self.last_response_id = response[0] self.last_response_args = response[1] def send_command(self, cmd, args=None): - message = "" if args == None: message = "manipulator-" + str(self.id_command) + " " + str(cmd) else: @@ -40,7 +38,6 @@ def send_command(self, cmd, args=None): return self.last_response_args # if don't get response a lot of time - def calibrate_small_robot(self): self.send_command("manipulator-calibrate_step_motor_1", 48) @@ -57,92 +54,55 @@ def calibrate_big_robot(self): self.send_command(48, 1) self.send_command(50, 1) - self.send_command(52, 1) - #rospy.sleep(3) + self.send_command(52, 1) + # rospy.sleep(3) self.send_command(32) self.send_command(48, 0) self.send_command(50, 0) - self.send_command(50, 0) self.send_command(52, 0) - self.send_command(25) - + self.send_command(25) def collect_puck_big(self): # Release grabber self.send_command(22) - #rospy.sleep(0.5) # Collector move default self.send_command(25) - #rospy.sleep(0.5) # Set pump to the wall self.send_command(20) - #rospy.sleep(0.5) # Set pump to the ground self.send_command(19) - #rospy.sleep(0.5) # Start pump self.send_command(17) - #rospy.sleep(0.5) # Set pump to the platform self.send_command(21) - #rospy.sleep(0.5) # Prop pack self.send_command(23) - #rospy.sleep(0.5) - # Stop pump + # Stop pump self.send_command(18) - #rospy.sleep(0.5) # Set pump to the wall self.send_command(20) - #rospy.sleep(0.5) # Grab pack self.send_command(24) - #rospy.sleep(0.5) # Collector move right/left self.send_command(32) - #rospy.sleep(0.5) # Make step down left / right collector self.send_command(50, 1) - #rospy.sleep(0.5) # Release grabber self.send_command(22) - def release_puck(self): - # Release grabber - self.send_command(33) - rospy.sleep(0.5) - # Collector move default - self.send_command(34) - rospy.sleep(0.5) - # Set pump to the wall - self.send_command(51, 1) - rospy.sleep(0.5) - # Release grabber - self.send_command(51, 1) - rospy.sleep(0.5) - # Collector move default - self.send_command(35) - rospy.sleep(0.5) - - def release_puck(self): self.send_command(33) - #rospy.sleep(0.5) self.send_command(34) - #rospy.sleep(0.5) self.send_command(51, 1) - #rospy.sleep(0.5) self.send_command(51, 1) - #rospy.sleep(0.5) self.send_command(52, 1) - self.send_command(35) - #rospy.sleep(0.5) - - def collect_puck(self): + self.send_command(35) + + def collect_puck(self): # Release grabber self.send_command(22) # Set pump to the wall diff --git a/eurobot_stm/scripts/tests/calibration.py b/eurobot_stm/scripts/tests/calibration.py new file mode 100644 index 0000000..1b526cf --- /dev/null +++ b/eurobot_stm/scripts/tests/calibration.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.calibrate_big_robot() diff --git a/eurobot_stm/scripts/tests/collect.py b/eurobot_stm/scripts/tests/collect.py new file mode 100644 index 0000000..e92e716 --- /dev/null +++ b/eurobot_stm/scripts/tests/collect.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.collect_puck_big() diff --git a/eurobot_stm/scripts/tests/release.py b/eurobot_stm/scripts/tests/release.py new file mode 100644 index 0000000..e5334d9 --- /dev/null +++ b/eurobot_stm/scripts/tests/release.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_puck() From 855d88940aa1332b2f39a042bb8eb069acd2ff62 Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Thu, 21 Feb 2019 17:32:47 +0300 Subject: [PATCH 32/40] add commands for small --- eurobot_stm/scripts/manipulator.py | 32 +++++++++++-------- .../tests/{collect.py => calibrate_big.py} | 2 +- .../{calibration.py => calibrate_small.py} | 2 +- .../tests/{release.py => collect_big.py} | 3 +- eurobot_stm/scripts/tests/collect_small.py | 4 +++ eurobot_stm/scripts/tests/release_big.py | 3 ++ eurobot_stm/scripts/tests/release_small.py | 3 ++ 7 files changed, 32 insertions(+), 17 deletions(-) rename eurobot_stm/scripts/tests/{collect.py => calibrate_big.py} (71%) rename eurobot_stm/scripts/tests/{calibration.py => calibrate_small.py} (68%) rename eurobot_stm/scripts/tests/{release.py => collect_big.py} (74%) create mode 100644 eurobot_stm/scripts/tests/collect_small.py create mode 100644 eurobot_stm/scripts/tests/release_big.py create mode 100644 eurobot_stm/scripts/tests/release_small.py diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 25bf561..71555af 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -38,10 +38,10 @@ def send_command(self, cmd, args=None): return self.last_response_args # if don't get response a lot of time - def calibrate_small_robot(self): - self.send_command("manipulator-calibrate_step_motor_1", 48) + def calibrate_small(self): + self.send_command(48) - def calibrate_big_robot(self): + def calibrate_big(self): # 1) collector move left # 2) start calibration right stepper # 3) make step down by right stepper @@ -65,7 +65,7 @@ def calibrate_big_robot(self): self.send_command(52, 0) self.send_command(25) - def collect_puck_big(self): + def collect_big(self): # Release grabber self.send_command(22) # Collector move default @@ -93,16 +93,7 @@ def collect_puck_big(self): # Release grabber self.send_command(22) - - def release_puck(self): - self.send_command(33) - self.send_command(34) - self.send_command(51, 1) - self.send_command(51, 1) - self.send_command(52, 1) - self.send_command(35) - - def collect_puck(self): + def collect_big(self): # Release grabber self.send_command(22) # Set pump to the wall @@ -123,3 +114,16 @@ def collect_puck(self): self.send_command(24) # Release grabber self.send_command(22) + + + def release_big(self): + self.send_command(33) + self.send_command(34) + self.send_command(51, 1) + self.send_command(51, 1) + self.send_command(52, 1) + self.send_command(35) + + def release_small(self): + pass + diff --git a/eurobot_stm/scripts/tests/collect.py b/eurobot_stm/scripts/tests/calibrate_big.py similarity index 71% rename from eurobot_stm/scripts/tests/collect.py rename to eurobot_stm/scripts/tests/calibrate_big.py index e92e716..c55aac3 100644 --- a/eurobot_stm/scripts/tests/collect.py +++ b/eurobot_stm/scripts/tests/calibrate_big.py @@ -1,4 +1,4 @@ from manipulator import Manipulator man = Manipulator() -man.collect_puck_big() +man.calibrate_big() diff --git a/eurobot_stm/scripts/tests/calibration.py b/eurobot_stm/scripts/tests/calibrate_small.py similarity index 68% rename from eurobot_stm/scripts/tests/calibration.py rename to eurobot_stm/scripts/tests/calibrate_small.py index 1b526cf..6515c03 100644 --- a/eurobot_stm/scripts/tests/calibration.py +++ b/eurobot_stm/scripts/tests/calibrate_small.py @@ -1,4 +1,4 @@ from manipulator import Manipulator man = Manipulator() -man.calibrate_big_robot() +man.calibrate_small() diff --git a/eurobot_stm/scripts/tests/release.py b/eurobot_stm/scripts/tests/collect_big.py similarity index 74% rename from eurobot_stm/scripts/tests/release.py rename to eurobot_stm/scripts/tests/collect_big.py index e5334d9..7207dfe 100644 --- a/eurobot_stm/scripts/tests/release.py +++ b/eurobot_stm/scripts/tests/collect_big.py @@ -1,3 +1,4 @@ from manipulator import Manipulator + man = Manipulator() -man.release_puck() +man.collect_big() diff --git a/eurobot_stm/scripts/tests/collect_small.py b/eurobot_stm/scripts/tests/collect_small.py new file mode 100644 index 0000000..95a74ac --- /dev/null +++ b/eurobot_stm/scripts/tests/collect_small.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.collect_small() diff --git a/eurobot_stm/scripts/tests/release_big.py b/eurobot_stm/scripts/tests/release_big.py new file mode 100644 index 0000000..b8919aa --- /dev/null +++ b/eurobot_stm/scripts/tests/release_big.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_big() diff --git a/eurobot_stm/scripts/tests/release_small.py b/eurobot_stm/scripts/tests/release_small.py new file mode 100644 index 0000000..6226cf6 --- /dev/null +++ b/eurobot_stm/scripts/tests/release_small.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_small() From 741db6ab934c80ab428f0322049dbcf9411c848c Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Thu, 21 Feb 2019 17:32:47 +0300 Subject: [PATCH 33/40] add commands for small robot --- eurobot_stm/scripts/manipulator.py | 34 +++++++++++-------- .../tests/{collect.py => calibrate_big.py} | 2 +- .../{calibration.py => calibrate_small.py} | 2 +- .../tests/{release.py => collect_big.py} | 3 +- eurobot_stm/scripts/tests/collect_small.py | 4 +++ eurobot_stm/scripts/tests/release_big.py | 3 ++ eurobot_stm/scripts/tests/release_small.py | 3 ++ 7 files changed, 33 insertions(+), 18 deletions(-) rename eurobot_stm/scripts/tests/{collect.py => calibrate_big.py} (71%) rename eurobot_stm/scripts/tests/{calibration.py => calibrate_small.py} (68%) rename eurobot_stm/scripts/tests/{release.py => collect_big.py} (74%) create mode 100644 eurobot_stm/scripts/tests/collect_small.py create mode 100644 eurobot_stm/scripts/tests/release_big.py create mode 100644 eurobot_stm/scripts/tests/release_small.py diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 25bf561..da4dcc2 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -7,7 +7,7 @@ class Manipulator(): def __init__(self): - # rospy.init_node("manuipulator_node", anonymous=True) + rospy.init_node("manuipulator_node", anonymous=True) self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) @@ -38,10 +38,10 @@ def send_command(self, cmd, args=None): return self.last_response_args # if don't get response a lot of time - def calibrate_small_robot(self): - self.send_command("manipulator-calibrate_step_motor_1", 48) + def calibrate_small(self): + self.send_command(48) - def calibrate_big_robot(self): + def calibrate_big(self): # 1) collector move left # 2) start calibration right stepper # 3) make step down by right stepper @@ -65,7 +65,7 @@ def calibrate_big_robot(self): self.send_command(52, 0) self.send_command(25) - def collect_puck_big(self): + def collect_big(self): # Release grabber self.send_command(22) # Collector move default @@ -93,16 +93,7 @@ def collect_puck_big(self): # Release grabber self.send_command(22) - - def release_puck(self): - self.send_command(33) - self.send_command(34) - self.send_command(51, 1) - self.send_command(51, 1) - self.send_command(52, 1) - self.send_command(35) - - def collect_puck(self): + def collect_big(self): # Release grabber self.send_command(22) # Set pump to the wall @@ -123,3 +114,16 @@ def collect_puck(self): self.send_command(24) # Release grabber self.send_command(22) + + + def release_big(self): + self.send_command(33) + self.send_command(34) + self.send_command(51, 1) + self.send_command(51, 1) + self.send_command(52, 1) + self.send_command(35) + + def release_small(self): + pass + diff --git a/eurobot_stm/scripts/tests/collect.py b/eurobot_stm/scripts/tests/calibrate_big.py similarity index 71% rename from eurobot_stm/scripts/tests/collect.py rename to eurobot_stm/scripts/tests/calibrate_big.py index e92e716..c55aac3 100644 --- a/eurobot_stm/scripts/tests/collect.py +++ b/eurobot_stm/scripts/tests/calibrate_big.py @@ -1,4 +1,4 @@ from manipulator import Manipulator man = Manipulator() -man.collect_puck_big() +man.calibrate_big() diff --git a/eurobot_stm/scripts/tests/calibration.py b/eurobot_stm/scripts/tests/calibrate_small.py similarity index 68% rename from eurobot_stm/scripts/tests/calibration.py rename to eurobot_stm/scripts/tests/calibrate_small.py index 1b526cf..6515c03 100644 --- a/eurobot_stm/scripts/tests/calibration.py +++ b/eurobot_stm/scripts/tests/calibrate_small.py @@ -1,4 +1,4 @@ from manipulator import Manipulator man = Manipulator() -man.calibrate_big_robot() +man.calibrate_small() diff --git a/eurobot_stm/scripts/tests/release.py b/eurobot_stm/scripts/tests/collect_big.py similarity index 74% rename from eurobot_stm/scripts/tests/release.py rename to eurobot_stm/scripts/tests/collect_big.py index e5334d9..7207dfe 100644 --- a/eurobot_stm/scripts/tests/release.py +++ b/eurobot_stm/scripts/tests/collect_big.py @@ -1,3 +1,4 @@ from manipulator import Manipulator + man = Manipulator() -man.release_puck() +man.collect_big() diff --git a/eurobot_stm/scripts/tests/collect_small.py b/eurobot_stm/scripts/tests/collect_small.py new file mode 100644 index 0000000..95a74ac --- /dev/null +++ b/eurobot_stm/scripts/tests/collect_small.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.collect_small() diff --git a/eurobot_stm/scripts/tests/release_big.py b/eurobot_stm/scripts/tests/release_big.py new file mode 100644 index 0000000..b8919aa --- /dev/null +++ b/eurobot_stm/scripts/tests/release_big.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_big() diff --git a/eurobot_stm/scripts/tests/release_small.py b/eurobot_stm/scripts/tests/release_small.py new file mode 100644 index 0000000..6226cf6 --- /dev/null +++ b/eurobot_stm/scripts/tests/release_small.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_small() From 53baa3602f0cc9392ae1b3a120d7d87e69c2a12c Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Thu, 21 Feb 2019 18:09:36 +0300 Subject: [PATCH 34/40] add normal tests + fix bugs --- eurobot_stm/scripts/STM_protocol.py | 2 +- eurobot_stm/scripts/manipulator.py | 2 +- eurobot_stm/scripts/tests/calibrate_big.py | 4 - eurobot_stm/scripts/tests/calibrate_small.py | 4 - eurobot_stm/scripts/tests/collect_big.py | 4 - eurobot_stm/scripts/tests/collect_small.py | 4 - eurobot_stm/scripts/tests/manipulator.py | 129 +++++++++++++++++++ eurobot_stm/scripts/tests/release_big.py | 3 - eurobot_stm/scripts/tests/release_small.py | 3 - eurobot_stm/scripts/tests/test.py | 39 ++++++ 10 files changed, 170 insertions(+), 24 deletions(-) delete mode 100644 eurobot_stm/scripts/tests/calibrate_big.py delete mode 100644 eurobot_stm/scripts/tests/calibrate_small.py delete mode 100644 eurobot_stm/scripts/tests/collect_big.py delete mode 100644 eurobot_stm/scripts/tests/collect_small.py create mode 100755 eurobot_stm/scripts/tests/manipulator.py delete mode 100644 eurobot_stm/scripts/tests/release_big.py delete mode 100644 eurobot_stm/scripts/tests/release_small.py create mode 100644 eurobot_stm/scripts/tests/test.py diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index b8f40fa..b6aa6b2 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -42,7 +42,7 @@ def __init__(self, serial_port, baudrate=115200): self.unpack_format = { 0x01: "=cccc", 0x07: "=fff", - 0x08: "=ccc", + 0x08: "=cc", 0x09: "=fff", 0x0e: "=cc", 0x0f: "=fff", diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index b2c52b5..aaa4142 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -65,7 +65,7 @@ def calibrate_big(self): self.send_command(52, 0) self.send_command(25) - def collect_big(self): + def collect_big(self, num): # Release grabber self.send_command(22) # Collector move default diff --git a/eurobot_stm/scripts/tests/calibrate_big.py b/eurobot_stm/scripts/tests/calibrate_big.py deleted file mode 100644 index c55aac3..0000000 --- a/eurobot_stm/scripts/tests/calibrate_big.py +++ /dev/null @@ -1,4 +0,0 @@ -from manipulator import Manipulator - -man = Manipulator() -man.calibrate_big() diff --git a/eurobot_stm/scripts/tests/calibrate_small.py b/eurobot_stm/scripts/tests/calibrate_small.py deleted file mode 100644 index 6515c03..0000000 --- a/eurobot_stm/scripts/tests/calibrate_small.py +++ /dev/null @@ -1,4 +0,0 @@ -from manipulator import Manipulator - -man = Manipulator() -man.calibrate_small() diff --git a/eurobot_stm/scripts/tests/collect_big.py b/eurobot_stm/scripts/tests/collect_big.py deleted file mode 100644 index 7207dfe..0000000 --- a/eurobot_stm/scripts/tests/collect_big.py +++ /dev/null @@ -1,4 +0,0 @@ -from manipulator import Manipulator - -man = Manipulator() -man.collect_big() diff --git a/eurobot_stm/scripts/tests/collect_small.py b/eurobot_stm/scripts/tests/collect_small.py deleted file mode 100644 index 95a74ac..0000000 --- a/eurobot_stm/scripts/tests/collect_small.py +++ /dev/null @@ -1,4 +0,0 @@ -from manipulator import Manipulator - -man = Manipulator() -man.collect_small() diff --git a/eurobot_stm/scripts/tests/manipulator.py b/eurobot_stm/scripts/tests/manipulator.py new file mode 100755 index 0000000..b2c52b5 --- /dev/null +++ b/eurobot_stm/scripts/tests/manipulator.py @@ -0,0 +1,129 @@ +#!/usr/bin/env python +import re + +import rospy +from std_msgs.msg import String + + +class Manipulator(): + def __init__(self): + rospy.init_node("manuipulator_node", anonymous=True) + + self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) + rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) + self.last_response_id = None + self.last_response_args = None + self.id_command = 1 + rospy.sleep(2) + + def response_callback(self, data): + response = data.data.split() + print ("RESPONSE=", response) + if re.match(r"manipulator-\d", response[0]): + self.last_response_id = response[0] + self.last_response_args = response[1] + + def send_command(self, cmd, args=None): + if args == None: + message = "manipulator-" + str(self.id_command) + " " + str(cmd) + else: + message = "manipulator-" + str(self.id_command) + " " + str(cmd) + " " + str(args) + while (True): + self.publisher.publish(String(message)) + + rospy.sleep(0.1) + if self.last_response_id == ("manipulator-" + str(self.id_command)): + if self.last_response_args == "OK": + self.id_command += 1 + return self.last_response_args + # if don't get response a lot of time + + def calibrate_small(self): + self.send_command(48) + + def calibrate_big(self): + # 1) collector move left + # 2) start calibration right stepper + # 3) make step down by right stepper + # 4) collector move right + # 5) start calibration left stepper + # 6) make step down by left stepper + # 7) make step down by left stepper + # 9) collector move default + self.send_command(33) + self.send_command(48, 1) + + self.send_command(50, 1) + self.send_command(52, 1) + # rospy.sleep(3) + self.send_command(32) + + self.send_command(48, 0) + self.send_command(50, 0) + + self.send_command(50, 0) + self.send_command(52, 0) + self.send_command(25) + + def collect_big(self): + # Release grabber + self.send_command(22) + # Collector move default + self.send_command(25) + # Set pump to the wall + self.send_command(20) + # Set pump to the ground + self.send_command(19) + # Start pump + self.send_command(17) + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # Grab pack + self.send_command(24) + # Collector move right/left + self.send_command(32) + # Make step down left / right collector + self.send_command(50, 1) + # Release grabber + self.send_command(22) + + def collect_small(self): + # Release grabber + self.send_command(22) + # Set pump to the wall + self.send_command(20) + # Set pump to the ground + self.send_command(19) + # Start pump + self.send_command(17) + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # Grab pack + self.send_command(24) + # Release grabber + self.send_command(22) + + + def release_big(self): + self.send_command(33) + self.send_command(34) + self.send_command(51, 1) + self.send_command(51, 1) + self.send_command(52, 1) + self.send_command(35) + + def release_small(self): + pass + diff --git a/eurobot_stm/scripts/tests/release_big.py b/eurobot_stm/scripts/tests/release_big.py deleted file mode 100644 index b8919aa..0000000 --- a/eurobot_stm/scripts/tests/release_big.py +++ /dev/null @@ -1,3 +0,0 @@ -from manipulator import Manipulator -man = Manipulator() -man.release_big() diff --git a/eurobot_stm/scripts/tests/release_small.py b/eurobot_stm/scripts/tests/release_small.py deleted file mode 100644 index 6226cf6..0000000 --- a/eurobot_stm/scripts/tests/release_small.py +++ /dev/null @@ -1,3 +0,0 @@ -from manipulator import Manipulator -man = Manipulator() -man.release_small() diff --git a/eurobot_stm/scripts/tests/test.py b/eurobot_stm/scripts/tests/test.py new file mode 100644 index 0000000..c4c1ac5 --- /dev/null +++ b/eurobot_stm/scripts/tests/test.py @@ -0,0 +1,39 @@ +import sys +import argparse +from manipulator import Manipulator + + +if __name__== '__main__': + + man = Manipulator() + + parser = argparse.ArgumentParser() + parser.add_argument("-s", "--size", + help="small or big") + parser.add_argument("-a", "--action", + help="action to make",) + args = parser.parse_args() + + if args.size == 0: + if args.action == 0: + man.calibrate_small() + elif args.action == 1: + man.collect_small() + elif args.action == 2: + man.release_small() + else: + exit("WRONG COMMAND") + elif args.size == 1: + if args.action == 0: + man.calibrate_big() + elif args.action == 1: + man.collect_big() + elif args.action == 2: + man.release_big() + else: + exit("WRONG COMMAND") + else: + exit("WRONG COMMAND") + + + From be586eec8ceb651cf3ce8f6718ac105e30b7de1d Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Mon, 25 Feb 2019 16:32:33 +0300 Subject: [PATCH 35/40] add tests --- eurobot_stm/scripts/tests/calibrate_big.py | 4 ++ eurobot_stm/scripts/tests/calibrate_small.py | 4 ++ eurobot_stm/scripts/tests/collect_big.py | 4 ++ eurobot_stm/scripts/tests/collect_small.py | 4 ++ eurobot_stm/scripts/tests/release_big.py | 3 ++ eurobot_stm/scripts/tests/release_small.py | 3 ++ eurobot_stm/scripts/tests/test.py | 39 -------------------- 7 files changed, 22 insertions(+), 39 deletions(-) create mode 100644 eurobot_stm/scripts/tests/calibrate_big.py create mode 100644 eurobot_stm/scripts/tests/calibrate_small.py create mode 100644 eurobot_stm/scripts/tests/collect_big.py create mode 100644 eurobot_stm/scripts/tests/collect_small.py create mode 100644 eurobot_stm/scripts/tests/release_big.py create mode 100644 eurobot_stm/scripts/tests/release_small.py delete mode 100644 eurobot_stm/scripts/tests/test.py diff --git a/eurobot_stm/scripts/tests/calibrate_big.py b/eurobot_stm/scripts/tests/calibrate_big.py new file mode 100644 index 0000000..8afef50 --- /dev/null +++ b/eurobot_stm/scripts/tests/calibrate_big.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.calibrate_big() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/calibrate_small.py b/eurobot_stm/scripts/tests/calibrate_small.py new file mode 100644 index 0000000..4716977 --- /dev/null +++ b/eurobot_stm/scripts/tests/calibrate_small.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.calibrate_small() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/collect_big.py b/eurobot_stm/scripts/tests/collect_big.py new file mode 100644 index 0000000..5435507 --- /dev/null +++ b/eurobot_stm/scripts/tests/collect_big.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.collect_big() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/collect_small.py b/eurobot_stm/scripts/tests/collect_small.py new file mode 100644 index 0000000..2197d04 --- /dev/null +++ b/eurobot_stm/scripts/tests/collect_small.py @@ -0,0 +1,4 @@ +from manipulator import Manipulator + +man = Manipulator() +man.collect_small() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/release_big.py b/eurobot_stm/scripts/tests/release_big.py new file mode 100644 index 0000000..28774b0 --- /dev/null +++ b/eurobot_stm/scripts/tests/release_big.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_big() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/release_small.py b/eurobot_stm/scripts/tests/release_small.py new file mode 100644 index 0000000..aca5880 --- /dev/null +++ b/eurobot_stm/scripts/tests/release_small.py @@ -0,0 +1,3 @@ +from manipulator import Manipulator +man = Manipulator() +man.release_small() \ No newline at end of file diff --git a/eurobot_stm/scripts/tests/test.py b/eurobot_stm/scripts/tests/test.py deleted file mode 100644 index c4c1ac5..0000000 --- a/eurobot_stm/scripts/tests/test.py +++ /dev/null @@ -1,39 +0,0 @@ -import sys -import argparse -from manipulator import Manipulator - - -if __name__== '__main__': - - man = Manipulator() - - parser = argparse.ArgumentParser() - parser.add_argument("-s", "--size", - help="small or big") - parser.add_argument("-a", "--action", - help="action to make",) - args = parser.parse_args() - - if args.size == 0: - if args.action == 0: - man.calibrate_small() - elif args.action == 1: - man.collect_small() - elif args.action == 2: - man.release_small() - else: - exit("WRONG COMMAND") - elif args.size == 1: - if args.action == 0: - man.calibrate_big() - elif args.action == 1: - man.collect_big() - elif args.action == 2: - man.release_big() - else: - exit("WRONG COMMAND") - else: - exit("WRONG COMMAND") - - - From 8c4c317dec271df2381fcdf234682b20dd318df4 Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Wed, 27 Feb 2019 15:34:27 +0300 Subject: [PATCH 36/40] fixed manipulator --- eurobot_stm/scripts/manipulator.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index aaa4142..305718e 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -7,7 +7,7 @@ class Manipulator(): def __init__(self): - rospy.init_node("manuipulator_node", anonymous=True) + # rospy.init_node("manuipulator_node", anonymous=True) self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) @@ -40,6 +40,7 @@ def send_command(self, cmd, args=None): def calibrate_small(self): self.send_command(48) + return True def calibrate_big(self): # 1) collector move left @@ -64,6 +65,7 @@ def calibrate_big(self): self.send_command(50, 0) self.send_command(52, 0) self.send_command(25) + return True def collect_big(self, num): # Release grabber @@ -92,6 +94,7 @@ def collect_big(self, num): self.send_command(50, 1) # Release grabber self.send_command(22) + return True def collect_small(self): # Release grabber @@ -114,6 +117,7 @@ def collect_small(self): self.send_command(24) # Release grabber self.send_command(22) + return True def release_big(self): @@ -123,7 +127,13 @@ def release_big(self): self.send_command(51, 1) self.send_command(52, 1) self.send_command(35) + return True def release_small(self): - pass - + self.send_command(51) + self.send_command(25) + self.send_command(50) + self.send_command(50) + self.send_command(32) + self.send_command(51) + return True \ No newline at end of file From eadcb5ddac52d1d341cd8132d0d773d0c58c2f95 Mon Sep 17 00:00:00 2001 From: NUKA-COLA Date: Thu, 28 Feb 2019 22:19:16 +0300 Subject: [PATCH 37/40] fix manipulator --- eurobot_stm/scripts/STM.py | 2 + eurobot_stm/scripts/manipulator.py | 87 +++++++++++++++++++++++++++--- 2 files changed, 81 insertions(+), 8 deletions(-) diff --git a/eurobot_stm/scripts/STM.py b/eurobot_stm/scripts/STM.py index 9043fc4..b012736 100755 --- a/eurobot_stm/scripts/STM.py +++ b/eurobot_stm/scripts/STM.py @@ -41,6 +41,8 @@ def parse_data(self, data): return id, cmd, args if __name__ == '__main__': + + #TODO::search for ports serial_port = "/dev/ttyUSB0" diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index 305718e..d635c7c 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -40,8 +40,11 @@ def send_command(self, cmd, args=None): def calibrate_small(self): self.send_command(48) + self.send_command(20) + self.send_command(25) return True + def calibrate_big(self): # 1) collector move left # 2) start calibration right stepper @@ -119,21 +122,89 @@ def collect_small(self): self.send_command(22) return True + def grab_and_suck_small(self): + # Release grabber + self.send_command(22) + # Set pump to the wall + self.send_command(20) + # Set pump to the ground + self.send_command(19) + # Start pump + self.send_command(17) + return True - def release_big(self): - self.send_command(33) - self.send_command(34) - self.send_command(51, 1) - self.send_command(51, 1) - self.send_command(52, 1) - self.send_command(35) + + def finish_collect_small(self): + # # Release grabber + # self.send_command(22) + # # Set pump to the wall + # self.send_command(20) + # # Set pump to the ground + # self.send_coand(19) + # # Start pump + # self.send_command(17) + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # Grab pack + self.send_command(24) + # Release grabber + self.send_command(22) + self.send_command(50) return True def release_small(self): + self.send_command(25) + self.send_command(50) + self.send_command(50) + self.send_command(50) + self.send_command(52) + self.send_command(32) + self.send_command(51) + self.send_command(51) + self.send_command(52) + self.send_command(25) + + self.send_command(50) + self.send_command(50) + self.send_command(52) + self.send_command(32) + self.send_command(51) + self.send_command(51) + self.send_command(52) + self.send_command(25) + + self.send_command(50) + self.send_command(50) + self.send_command(52) + self.send_command(32) + self.send_command(51) self.send_command(51) + self.send_command(52) self.send_command(25) + self.send_command(50) self.send_command(50) + self.send_command(52) self.send_command(32) self.send_command(51) - return True \ No newline at end of file + self.send_command(51) + self.send_command(52) + self.send_command(25) + return True + + + def release_big(self): + self.send_command(33) + self.send_command(34) + self.send_command(51, 1) + self.send_command(51, 1) + self.send_command(52, 1) + self.send_command(35) + return True + From 4706d3d34561b61f8ead0de67bd65c975ddaec73 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Tue, 5 Mar 2019 17:06:39 +0300 Subject: [PATCH 38/40] some fixes --- eurobot_stm/scripts/STM_protocol.py | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 1bcc3c8..0af107c 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -24,10 +24,10 @@ def __init__(self, serial_port, baudrate=115200): 0x12: "=", 0x13: "=", 0x14: "=", - 0x15: "=", - 0x16: "=", - 0x17: "=", - 0x18: "=" + 0x15: "=", + 0x16: "=", + 0x17: "=", + 0x18: "=" } self.unpack_format = { @@ -42,10 +42,10 @@ def __init__(self, serial_port, baudrate=115200): 0x12: "=cc", 0x13: "=cc", 0x14: "=cc", - 0x15: "=cc", - 0x16: "=cc", - 0x17: "=cc", - 0x18: "=cc" + 0x15: "=cc", + 0x16: "=cc", + 0x17: "=cc", + 0x18: "=cc" } self.response_bytes = { @@ -60,10 +60,10 @@ def __init__(self, serial_port, baudrate=115200): 0x12: 2, 0x13: 2, 0x14: 2, - 0x15: 2, - 0x16: 2, - 0x17: 2, - 0x18: 2 + 0x15: 2, + 0x16: 2, + 0x17: 2, + 0x18: 2 } def send(self, cmd, args): From 064cdc9d48c35cec0eabd50913d0823379d09b0b Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Sun, 17 Mar 2019 14:36:39 +0300 Subject: [PATCH 39/40] add new commands --- eurobot_stm/scripts/STM_protocol.py | 9 + eurobot_stm/scripts/manipulator.py | 304 ++++++++++++++++++++-------- 2 files changed, 227 insertions(+), 86 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index 1c46480..f0e58b6 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -13,6 +13,9 @@ def __init__(self, serial_port, baudrate=115200): self.ser = serial.Serial(serial_port,baudrate=baudrate, timeout = 0.01) self.pack_format = { 0x01: "=cccc", + 0x02: "=", + 0x03: "=", + 0x04: "=", 0x07: "=", 0x08: "=fff", 0x09: "=", @@ -41,6 +44,9 @@ def __init__(self, serial_port, baudrate=115200): self.unpack_format = { 0x01: "=cccc", + 0x02: "=cc", + 0x03: "=B", + 0x04: "=B", 0x07: "=fff", 0x08: "=cc", 0x09: "=fff", @@ -69,6 +75,9 @@ def __init__(self, serial_port, baudrate=115200): self.response_bytes = { 0x01: 4, + 0x02: 2, + 0x03: 1, + 0x04: 1, 0x07: 12, 0x08: 2, 0x09: 12, diff --git a/eurobot_stm/scripts/manipulator.py b/eurobot_stm/scripts/manipulator.py index d635c7c..b838449 100755 --- a/eurobot_stm/scripts/manipulator.py +++ b/eurobot_stm/scripts/manipulator.py @@ -5,20 +5,50 @@ from std_msgs.msg import String -class Manipulator(): +class Manipulator(object): def __init__(self): - # rospy.init_node("manuipulator_node", anonymous=True) + rospy.init_node("manipulator_node", anonymous=True) - self.publisher = rospy.Publisher("/secondary_robot/stm_command", String, queue_size=10) - rospy.Subscriber("/secondary_robot/stm_response", String, self.response_callback) + self.robot_name = rospy.get_param("robot_name") + + self.response_publisher = rospy.Publisher("manipulator/response", String, queue_size=10) + rospy.Subscriber("manipulator/command", String, self.command_callback) + + self.publisher = rospy.Publisher("stm_command", String, queue_size=10) + rospy.Subscriber("stm_response", String, self.response_callback) self.last_response_id = None self.last_response_args = None self.id_command = 1 rospy.sleep(2) + def command_callback(self, data): + command = data.data.split() + cmd_id = command[0] + print("CMD_ID=", cmd_id) + cmd = command[1] + print("CMD=", cmd) + if cmd == "default": + self.calibrate() + elif cmd == "manipulator_wall": + self.set_manipulator_wall() + elif cmd == "manipulator_up": + self.set_manipulator_up() + elif cmd == "take_ground": + self.take_ground() + elif cmd == "complete_ground_collect": + self.complete_ground_collect() + elif cmd == "start_collect_wall": + self.start_collect_wall() + elif cmd == "complete_collect_wall": + self.complete_collect_wall() + elif cmd == "collect_ground": + self.collect_small() + + self.response_publisher.publish(cmd_id + " success") + def response_callback(self, data): response = data.data.split() - print ("RESPONSE=", response) + print("RESPONSE=", response) if re.match(r"manipulator-\d", response[0]): self.last_response_id = response[0] self.last_response_args = response[1] @@ -38,37 +68,60 @@ def send_command(self, cmd, args=None): return self.last_response_args # if don't get response a lot of time - def calibrate_small(self): - self.send_command(48) - self.send_command(20) - self.send_command(25) - return True + def calibrate(self): + if self.robot_name == "main_robot": + self.send_command(33) + self.send_command(48, 1) + self.send_command(50, 1) + self.send_command(52, 1) + # rospy.sleep(3) + self.send_command(32) - def calibrate_big(self): - # 1) collector move left - # 2) start calibration right stepper - # 3) make step down by right stepper - # 4) collector move right - # 5) start calibration left stepper - # 6) make step down by left stepper - # 7) make step down by left stepper - # 9) collector move default - self.send_command(33) - self.send_command(48, 1) + self.send_command(48, 0) + self.send_command(50, 0) - self.send_command(50, 1) - self.send_command(52, 1) - # rospy.sleep(3) - self.send_command(32) + self.send_command(50, 0) + self.send_command(52, 0) + self.send_command(25) + return True + elif self.robot_name == "secondary_robot": + self.send_command(48) + self.send_command(21) + self.send_command(25) + return True - self.send_command(48, 0) - self.send_command(50, 0) - - self.send_command(50, 0) - self.send_command(52, 0) - self.send_command(25) - return True + # def calibrate_small(self): + # self.send_command(48) + # self.send_command(20) + # self.send_command(25) + # return True + # + # + # def calibrate_big(self): + # # 1) collector move left + # # 2) start calibration right stepper + # # 3) make step down by right stepper + # # 4) collector move right + # # 5) start calibration left stepper + # # 6) make step down by left stepper + # # 7) make step down by left stepper + # # 9) collector move default + # self.send_command(33) + # self.send_command(48, 1) + # + # self.send_command(50, 1) + # self.send_command(52, 1) + # # rospy.sleep(3) + # self.send_command(32) + # + # self.send_command(48, 0) + # self.send_command(50, 0) + # + # self.send_command(50, 0) + # self.send_command(52, 0) + # self.send_command(25) + # return True def collect_big(self, num): # Release grabber @@ -99,64 +152,137 @@ def collect_big(self, num): self.send_command(22) return True - def collect_small(self): - # Release grabber - self.send_command(22) - # Set pump to the wall - self.send_command(20) - # Set pump to the ground - self.send_command(19) - # Start pump - self.send_command(17) - # Set pump to the platform - self.send_command(21) - # Prop pack - self.send_command(23) - # Stop pump - self.send_command(18) - # Set pump to the wall + # def collect_ground_secondary(self): + # # Release grabber + # self.send_command(22) + # # Set pump to the wall + # self.send_command(20) + # # Set pump to the ground + # self.send_command(19) + # # Start pump + # self.send_command(17) + # # Set pump to the platform + # self.send_command(21) + # # Prop pack + # self.send_command(23) + # # Stop pump + # self.send_command(18) + # # Set pump to the wall + # self.send_command(20) + # # Grab pack + # self.send_command(24) + # # Release grabber + # self.send_command(22) + # return True + + def take_ground(self): + if self.robot_name == "main_robot": + pass + if self.robot_name == "secondary_robot": + # Release grabber + self.send_command(22) + # Set pump to the wall + self.send_command(20) + # Set pump to the ground + self.send_command(19) + # Start pump + self.send_command(17) + return True + + def set_manipulator_wall(self): self.send_command(20) - # Grab pack + + def set_manipulator_up(self): self.send_command(24) - # Release grabber - self.send_command(22) - return True + self.send_command(21) - def grab_and_suck_small(self): - # Release grabber - self.send_command(22) - # Set pump to the wall - self.send_command(20) - # Set pump to the ground - self.send_command(19) - # Start pump - self.send_command(17) - return True + def complete_ground_collect(self): + if self.robot_name == "main_robot": + pass + if self.robot_name == "secondary_robot": + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # Grab pack + self.send_command(24) + # Release grabber + self.send_command(22) + self.send_command(50) + return True - def finish_collect_small(self): - # # Release grabber - # self.send_command(22) - # # Set pump to the wall - # self.send_command(20) - # # Set pump to the ground - # self.send_coand(19) - # # Start pump - # self.send_command(17) - # Set pump to the platform - self.send_command(21) - # Prop pack - self.send_command(23) - # Stop pump - self.send_command(18) - # Set pump to the wall - self.send_command(20) - # Grab pack - self.send_command(24) - # Release grabber - self.send_command(22) - self.send_command(50) - return True + # def collect_wall(self): + # if self.robot_name == "main_robot": + # pass + # if self.robot_name == "secondary_robot": + # # Release grabber + # self.send_command(22) + # # Set pump to the wall + # self.send_command(20) + # rospy.sleep(0.5) + # # Start pump + # self.send_command(17) + # # Set pump to the platform + # self.send_command(21) + # # Prop pack + # self.send_command(23) + # # Stop pump + # self.send_command(18) + # # Set pump to the wall + # self.send_command(20) + # # grab pack + # self.send_command(24) + # + # # Release grabber + # self.send_command(22) + # # Set pump to the platform + # # self.send_command(21) + # + # self.send_command(50) + # return True + + def start_collect_wall(self): + if self.robot_name == "main_robot": + pass + if self.robot_name == "secondary_robot": + # Release grabber + self.send_command(22) + # Set pump to the wall + self.send_command(20) + # rospy.sleep(0.5) + # Start pump + self.send_command(17) + return True + + def complete_collect_wall(self): + if self.robot_name == "main_robot": + pass + if self.robot_name == "secondary_robot": + rospy.sleep(0.3) + + # Set pump to the platform + self.send_command(21) + # Prop pack + self.send_command(23) + # Stop pump + self.send_command(18) + # Set pump to the wall + self.send_command(20) + # grab pack + self.send_command(24) + + # Release grabber + self.send_command(22) + # Set pump to the platform + # self.send_command(21) + + self.send_command(50) + return True def release_small(self): self.send_command(25) @@ -198,7 +324,6 @@ def release_small(self): self.send_command(25) return True - def release_big(self): self.send_command(33) self.send_command(34) @@ -208,3 +333,10 @@ def release_big(self): self.send_command(35) return True + +if __name__ == '__main__': + try: + manipulator = Manipulator() + rospy.spin() + except rospy.ROSInterruptException: + pass \ No newline at end of file From 1def55358ac34391a74d5d2465175f44bddced94 Mon Sep 17 00:00:00 2001 From: alexey-kashapov Date: Sun, 17 Mar 2019 14:42:15 +0300 Subject: [PATCH 40/40] fix spaces --- eurobot_stm/scripts/STM_protocol.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/eurobot_stm/scripts/STM_protocol.py b/eurobot_stm/scripts/STM_protocol.py index f0e58b6..89a7c91 100755 --- a/eurobot_stm/scripts/STM_protocol.py +++ b/eurobot_stm/scripts/STM_protocol.py @@ -26,10 +26,10 @@ def __init__(self, serial_port, baudrate=115200): 0x12: "=", 0x13: "=", 0x14: "=", - 0x15: "=", - 0x16: "=", - 0x17: "=", - 0x18: "=", + 0x15: "=", + 0x16: "=", + 0x17: "=", + 0x18: "=", 0x19: "=", 0x20: "=", 0x21: "=B", @@ -39,7 +39,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=", 0x32: "=B", 0x33: "=B", - 0x34: "=B" + 0x34: "=B" } self.unpack_format = { @@ -70,7 +70,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: "=cc", 0x32: "=cc", 0x33: "=cc", - 0x34: "=cc" + 0x34: "=cc" } self.response_bytes = { @@ -101,7 +101,7 @@ def __init__(self, serial_port, baudrate=115200): 0x31: 2, 0x32: 2, 0x33: 2, - 0x34: 2 + 0x34: 2 } def send(self, cmd, args):