Added applied robotics code to archive.

This commit is contained in:
2018-08-22 14:49:49 -07:00
parent 5cbceb42d7
commit a56690ca18
89 changed files with 38750 additions and 0 deletions

View File

@@ -0,0 +1,200 @@
cmake_minimum_required(VERSION 2.8.3)
project(denso_master)
## 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
rospy
std_msgs
message_generation
)
## 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 run_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 run_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
DensoStatusMessage.msg
# 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 run_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 network_master
CATKIN_DEPENDS rospy std_msgs message_runtime
# 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}/network_master.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/network_master_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_network_master.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)

View File

@@ -0,0 +1,11 @@
float32[] positions
float32[] joints
bool motor_enabled
bool arm_normal
bool arm_busy
string error
uint8 speed
uint8 tank_psi

View File

@@ -0,0 +1,67 @@
<?xml version="1.0"?>
<package format="2">
<name>denso_master</name>
<version>0.0.0</version>
<description>The network_master package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="denso@todo.todo">caperren</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/network_master</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@@ -0,0 +1,121 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import socket
import json
from network_master.msg import DensoStatusMessage
from std_msgs.msg import Float32MultiArray, Bool, UInt8
#####################################
# Global Variables
#####################################
NODE_NAME = "robot_control_control_sender"
DEFAULT_HERTZ = 100
DEFAULT_IP = "192.168.1.5"
DEFAULT_PORT = 9877
ABS_POS_TOPIC = "denso_control/absolute_position"
REL_POS_TOPIC = "denso_control/relative_position"
ABS_JOINT_TOPIC = "denso_control/absolute_joints"
REL_JOINT_TOPIC = "denso_control/relative_joints"
SPEED_TOPIC = "denso_control/speed"
MOTOR_TOPIC = "denso_control/motors_enabled"
#####################################
# ControlSender Class Definition
#####################################
class ControlSender(object):
def __init__(self):
super(ControlSender, self).__init__()
rospy.init_node(NODE_NAME)
self.address = rospy.get_param("~server_address", DEFAULT_IP)
self.port = rospy.get_param("~server_port", DEFAULT_PORT)
self.abs_position_topic = rospy.get_param("~abs_position_topic_sub", ABS_POS_TOPIC)
self.rel_position_topic = rospy.get_param("~rel_position_topic_sub", REL_POS_TOPIC)
self.abs_joint_topic = rospy.get_param("~abs_joint_topic_sub", ABS_JOINT_TOPIC)
self.rel_joint_topic = rospy.get_param("~rel_joint_topic_sub", REL_JOINT_TOPIC)
self.speed_topic = rospy.get_param("~speed_topic_sub", SPEED_TOPIC)
self.motor_topic = rospy.get_param("~motor_control_topic_sub", MOTOR_TOPIC)
self.abs_position_subscriber = rospy.Subscriber(self.abs_position_topic, Float32MultiArray, self.abs_position_callback)
self.rel_position_subscriber = rospy.Subscriber(self.rel_position_topic, Float32MultiArray, self.rel_position_callback)
self.abs_joints_subscriber = rospy.Subscriber(self.abs_joint_topic, Float32MultiArray, self.abs_joints_callback)
self.rel_joints_subscriber = rospy.Subscriber(self.rel_joint_topic, Float32MultiArray, self.rel_joints_callback)
self.speed_subscriber = rospy.Subscriber(self.speed_topic, UInt8, self.speed_control_callback)
self.speed_subscriber = rospy.Subscriber(self.motor_topic, Bool, self.motor_control_callback)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.control_tcp_client = None
self.command_queue = []
# ########### Start class ##########
self.run()
def run(self):
self.initalize_tcp_client()
while not rospy.is_shutdown():
start_time = time()
self.process_command_queue_item()
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def initalize_tcp_client(self):
self.control_tcp_client = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.control_tcp_client.connect((self.address, self.port))
def process_command_queue_item(self):
if self.command_queue:
data = self.command_queue[0]
del self.command_queue[0]
try:
self.control_tcp_client.sendall(json.dumps(data))
self.control_tcp_client.sendall("#####")
# print "sending"
except:
pass
def speed_control_callback(self, data):
# print data.data
self.command_queue.append({"change_robot_speed": data.data})
def motor_control_callback(self, data):
self.command_queue.append({"enable_motors": data.data})
def abs_position_callback(self, data):
# print data.data
self.command_queue.append({"move_position_abs": data.data})
def rel_position_callback(self, data):
# print data.data
self.command_queue.append({"move_position_rel": data.data})
def abs_joints_callback(self, data):
# print data.data
self.command_queue.append({"move_joint_abs": data.data})
def rel_joints_callback(self, data):
# print data.data
self.command_queue.append({"move_joint_rel": data.data})
if __name__ == "__main__":
ControlSender()

View File

@@ -0,0 +1,24 @@
#!/usr/bin/env python
import rospy
from std_msgs.msg import Float32MultiArray, UInt8
import time
import random
rospy.init_node("another_test")
pub = rospy.Publisher("/denso_control/relative_joints", Float32MultiArray, queue_size=1)
message = Float32MultiArray()
time.sleep(2)
while not rospy.is_shutdown():
message.data = (0, 0, 0.25, 0, 0, 0) # Catch
pub.publish(message)
time.sleep(3)

View File

@@ -0,0 +1,12 @@
import rospy
from std_msgs.msg import Float32MultiArray
rospy.init_node("ano")
pub = rospy.Publisher("/denso_control/relative_joints", Float32MultiArray, queue_size=1)
message = Float32MultiArray()
message.data = (20, 0, 0, 0, 0, 0)
pub.publish(message)

View File

@@ -0,0 +1,112 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import socket
import json
from network_master.msg import DensoStatusMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "robot_control_status_receiver"
DEFAULT_HERTZ = 1000
DEFAULT_IP = "192.168.1.5"
DEFAULT_PORT = 9876
DEFAULT_STATUS_TOPIC = "denso_status"
#####################################
# ControlSender Class Definition
#####################################
class StatusReceiver(object):
def __init__(self):
super(StatusReceiver, self).__init__()
rospy.init_node(NODE_NAME)
self.address = rospy.get_param("~server_address", DEFAULT_IP)
self.port = rospy.get_param("~server_port", DEFAULT_PORT)
self.status_publish_topic = rospy.get_param("~status_topic_pub", DEFAULT_STATUS_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.status_publisher = rospy.Publisher(self.status_publish_topic, DensoStatusMessage, queue_size=1)
self.status_tcp_client = None
self.pound_count = 0
self.current_message = ""
# ########### Start class ##########
self.run()
def run(self):
self.initalize_tcp_client()
while not rospy.is_shutdown():
start_time = time()
self.current_message += self.status_tcp_client.recv(4096)
found_pound = self.current_message.find("#####")
if found_pound != -1:
split_message = str(self.current_message[:found_pound])
self.current_message = self.current_message[found_pound + 5:]
try:
json_message = json.loads(split_message)
message = DensoStatusMessage()
message.positions = (
json_message["position"]["x"],
json_message["position"]["y"],
json_message["position"]["z"],
json_message["position"]["rx"],
json_message["position"]["ry"],
json_message["position"]["rz"],
json_message["position"]["fig"]
)
message.joints = (
json_message["joints"]["1"],
json_message["joints"]["2"],
json_message["joints"]["3"],
json_message["joints"]["4"],
json_message["joints"]["5"],
json_message["joints"]["6"],
)
message.motor_enabled = json_message["statuses"]["motor_enabled"]
message.arm_normal = json_message["statuses"]["arm_normal"]
message.error = json_message["statuses"]["error"]
message.speed = json_message["statuses"]["speed"]
message.arm_busy = json_message["statuses"]["arm_busy"]
message.tank_psi = json_message["statuses"]["tank_psi"]
self.status_publisher.publish(message)
except Exception, e:
print e
self.current_message = ""
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def initalize_tcp_client(self):
self.status_tcp_client = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.status_tcp_client.connect((self.address, self.port))
if __name__ == '__main__':
StatusReceiver()