diff --git a/spider_control/CMakeLists.txt b/spider_control/CMakeLists.txt index 4cb4351448e9c86ed48f7767462287b0471381ed..b6d1bb0aae45c75aec37b29ff78ac59d72777b91 100644 --- a/spider_control/CMakeLists.txt +++ b/spider_control/CMakeLists.txt @@ -11,6 +11,9 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs + message_generation + geometry_msgs + sensor_msgs ) ## System dependencies are found with CMake's conventions @@ -47,18 +50,21 @@ find_package(catkin REQUIRED COMPONENTS ## * 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 -# ) +#add_message_files( + #DIRECTORY + #msg + #FILES + #geometry_msgs + #sensor_msgs + #Message2.msg + #) ## Generate services in the 'srv' folder -# add_service_files( -# FILES -# Service1.srv + #add_service_files( + # FILES + #ReturnJointStates.srv # Service2.srv -# ) + #) ## Generate actions in the 'action' folder # add_action_files( @@ -68,10 +74,12 @@ find_package(catkin REQUIRED COMPONENTS # ) ## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# std_msgs # Or other packages containing msgs -# ) + #generate_messages( + #DEPENDENCIES + #std_msgs # Or other packages containing msgs + # geometry_msgs + # sensor_msgs +#) ################################################ ## Declare ROS dynamic reconfigure parameters ## @@ -105,7 +113,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_package( # INCLUDE_DIRS include # LIBRARIES spider_control -# CATKIN_DEPENDS roscpp rospy stdmsgs + CATKIN_DEPENDS roscpp rospy stdmsgs message_runtime geometry_msgs sensor_msgs # DEPENDS system_lib ) @@ -128,7 +136,7 @@ include_directories( ## 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}) +#add_dependencies(spider_control spider_control_generate_messages_cpp) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context @@ -163,6 +171,12 @@ include_directories( # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) +install(DIRECTORY config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + ## Mark executables and/or libraries for installation # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node diff --git a/spider_control/__pycache__/knowledge_transfer.cpython-36.pyc b/spider_control/__pycache__/knowledge_transfer.cpython-36.pyc new file mode 100644 index 0000000000000000000000000000000000000000..59e76eea770b56bff6b423896ed0d0e9b219612c Binary files /dev/null and b/spider_control/__pycache__/knowledge_transfer.cpython-36.pyc differ diff --git a/spider_control/__pycache__/leg_dynamics.cpython-36.pyc b/spider_control/__pycache__/leg_dynamics.cpython-36.pyc new file mode 100644 index 0000000000000000000000000000000000000000..9d5ebba92260dd5953528556cd67848afbcadde4 Binary files /dev/null and b/spider_control/__pycache__/leg_dynamics.cpython-36.pyc differ diff --git a/spider_control/__pycache__/my_network.cpython-36.pyc b/spider_control/__pycache__/my_network.cpython-36.pyc new file mode 100644 index 0000000000000000000000000000000000000000..4c4d545440c0222ff1bf6c7eabc39ffc5495aee8 Binary files /dev/null and b/spider_control/__pycache__/my_network.cpython-36.pyc differ diff --git a/spider_control/client_secrets.json b/spider_control/client_secrets.json new file mode 100644 index 0000000000000000000000000000000000000000..73a9293ea94d580ede90a2e9fb73db5af76afa98 --- /dev/null +++ b/spider_control/client_secrets.json @@ -0,0 +1 @@ +{"web":{"client_id":"810108153188-48jg15brjb431qbi8jvj4rrpi3hg91t3.apps.googleusercontent.com","project_id":"thesis-249808","auth_uri":"https://accounts.google.com/o/oauth2/auth","token_uri":"https://oauth2.googleapis.com/token","auth_provider_x509_cert_url":"https://www.googleapis.com/oauth2/v1/certs","client_secret":"9_lrPUdU3RUMrVIMoUgzxVnW","redirect_uris":["http://localhost:8080/"]}} \ No newline at end of file diff --git a/spider_control/config/spider_control.yaml b/spider_control/config/spider_control.yaml index d51d2e42111460490270a5f71f272aff695d2d1c..9d1ae80cbab2d17841b3e97a37fbeab9048a8610 100644 --- a/spider_control/config/spider_control.yaml +++ b/spider_control/config/spider_control.yaml @@ -6,108 +6,126 @@ spider: # Position Controllers --------------------------------------- joint_1_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_1_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_1_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_1_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_1_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_1_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_2_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_2_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_2_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_2_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_2_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_2_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_3_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_3_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_3_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_3_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_3_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_3_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_4_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_4_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_4_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_4_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_4_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_4_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_5_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_5_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_5_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_5_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_5_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_5_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_6_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_6_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_6_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_6_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_6_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_6_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_7_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_7_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_7_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_7_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_7_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_7_3 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_8_1_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_8_1 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_8_2_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_8_2 - pid: {p: 1.0, i: 1.0, d: 0.0} joint_8_3_position_controller: - type: effort_controllers/JointPositionController + type: position_controllers/JointPositionController joint: joint_8_3 - pid: {p: 1.0, i: 1.0, d: 0.0} - - - - - - - - + + gazebo_ros_control/pid_gains: + joint_1_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_1_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_1_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_2_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_2_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_2_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_3_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_3_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_3_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_4_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_4_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_4_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_5_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_5_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_5_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_6_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_6_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_6_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_7_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_7_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_7_3: {p: 30.0, i: 20.0, d: 5.0} + + joint_8_1: {p: 30.0, i: 20.0, d: 5.0} + + joint_8_2: {p: 30.0, i: 20.0, d: 5.0} + + joint_8_3: {p: 30.0, i: 20.0, d: 5.0} + \ No newline at end of file diff --git a/spider_control/control.py b/spider_control/control.py old mode 100644 new mode 100755 index b758dcebafa00f4dd66b86ce4f0cc641d7940823..555a86cb3076993e72857b91c1ea2453776789ac --- a/spider_control/control.py +++ b/spider_control/control.py @@ -1,147 +1,105 @@ -#!/usr/bin/env python3.6.7 +#!/usr/bin/python3 + import tensorflow as tf import numpy as np import roslib roslib.load_manifest('joint_states_listener') roslib.load_manifest('spider_control') -#import pylab as plt +from matplotlib import pylab +import pylab as plt import math import threading -from geometry_msgs.msgs import * +from geometry_msgs import * import rospy, yaml, sys -from osrf_msgs.msg import JointCommands +#from osrf_msgs.msg import JointCommands from sensor_msgs.msg import JointState from joint_states_listener.srv import * +#from joint_States_listener.srv import ReturnJointStates import threading import time from std_msgs.msg import Float64 from std_msgs.msg import Header -#from sklearn.multiclass import OneVsRestClassifier -#from sklearn.svm import LinearSVC - -tf.enable_eager_execution() - -class LatestJointStates: - - - def __init__(self): - rospy.init_node('Joint state Listener') - self.lock = threading.Lock() - self.name = [] - self.position = [] - self.velocity = [] - self.effort = [] - self.thread = threading.Thread(target=self.joint_States_listener) - self.thread.start() - - s = rospy.Service('return_joint_states', ReturnJointStates, self.return_joint_states) - #thread the function to listen to joint state messages - def joint_states_listener(self): - rospy.Subscriber('joint_states', JointState, self.joint_states_callback) - rospy.spin() - - #callback function inorder to save the values when joint_states are available - def joint_States_callback(self, msg): - self.lock.acquire() - self.name = msg.name - self.position = msg.position - self.velocity = msg.velocity - self.effort = msg.effort - self.lock.release() - #function that returns joint variables for joint names that are given - def return_joint_state(self, joint_name): - - #no messages - if self.name==[]: - rospy.logerr("no robot_State messages received \n") - return 0, 0, 0, 0 - #return info for this joint - self.lock.acquire() - if joint_name in self.name: - index = self.name.index(joint_name) - position = self.position[index] - velocity = self.velocity[index] - effort = self.effort[index] - - #joint name not found - else: - rospy.logerr("Joint %s not found", (joint_name)) - self.lock.release() - return 0, 0, 0, 0 - self.lock.release() - return 1, position, velocity, effort - #server callback to return array of position velocity and effort of the called joint names - - def return_joint_states(self, req): - joints_found = [] - positions = [] - velocities = [] - efforts = [] - for joint_name in req.name: - (found, position, velocity, effort)=self.return_joint_state(joint_name) - joints_found.append(found) - positions.append(position) - velocities.append(velocity) - efforts.append(effort) - return ReturnJointStatesResponse(joints_found, positions, velocities, efforts) - -def callback(msg): - - #log the message data +from sklearn.multiclass import OneVsRestClassifier +from sklearn.svm import LinearSVC + +#tf.compat.v1.enable_eager_execution() + +#global g_joint_states +#global g_position +#global g_pos1 +g_joint_states = None +g_position = None #np.ones(24)#np.empty(24, dtype = int) +g_pos1 = None +#global tactile_states +tactile_states = None #np.ones(8)#np.empty(8, dtype = int) +def tactile_callback(data): rospy.loginfo(msg.data) - return msg.data - -def listener(): - rospy.init_node("tactile_listener") - tactile_sub = rospy.Subscriber("/sr_tactile/touch/ff", Float64, callback) - global tactile_1 #global variable to store tactile value for the leg 1 - global tactile_2 #global variable to store tactile value for the leg 2 - global tactile_3 #global variable to store tactile value for the leg 3 - global tactile_4 #global variable to store tactile value for the leg 4 - global tactile_5 #global variable to store tactile value for the leg 5 - global tactile_6 #global variable to store tactile value for the leg 6 - global tactile_7 #global variable to store tactile value for the leg 7 - global tactile_8 #global variable to store tactile value for the leg 8 - tactile_1 = tactile_sub[0] - tactile_2 = tactile_sub[1] - tactile_3 = tactile_sub[2] - tactile_4 = tactile_sub[3] - tactile_5 = tactile_sub[4] - tactile_6 = tactile_sub[5] - tactile_7 = tactile_sub[6] - tactile_8 = tactile_sub[7] - rospy.spin() - return tactile_1, tactile_2, tactile_3, tactile_4, tactile_5, tactile_6, tactile_7, tactile_8 - - - -def call_return_joint_states(joint_names): - rospy.wait_for_service("return_joint_states") - try: - s = rospy.ServiceProxy("return_joint_States", ReturnJointStates) - resp = s(joint_names) - except rospy.ServiceException as e: - print("error when calling return_joint_states: %s"%e) - sys.exit(1) - for (ind, joint_name) in enumerate(joint_names): - if(not resp.found[ind]): - print("joint %s not found"%joint_name) - return resp.position, resp.velocity, resp.effort - -def talker(jointname , position): + global tactile_states + tactile_states = data.data + +def joint_callback(data): + rospy.loginfo(data.position) + global g_joint_states + global g_position + global g_pos1 + g_joint_states = data + #for i in len(data.position): + #g_position[i] = data.position[i] + g_position = data.position + if len(data.position) > 0: + print("jointstate more than 0") + g_pos1 = data.position[0] + #print(g_position) + +def timer_callback(event): # Type rospy.TimerEvent + print('timer_cb (' + str(event.current_real) + '): g_positions is') + print(str(None) if g_positions is None else str(g_positions)) + +def timer_callback_tactile(event): + print('timer_cb_t('+str(event.current_real) + '): tactile_states is') + print(str(None) if tactile_states is None else str(tactile_states)) + + + + +def joint_modifier(*args): + #choice describes what the node is supposed to do whether act as publisher or subscribe to joint states or tactile sensors + rospy.init_node('joint_listener_publisher', anonymous=True) pub1 = rospy.Publisher('joint_states', JointState, queue_size = 10) - rospy.init_node('joint_state_publisher') - rate = rospy.Rate(10) - while not rospy.is_shutdown(): + if(len(args)>1): + choice = args[0] + joint_name = args[1] + position = args[2] + else: + choice = args[0] + if (choice == 1): + rate = rospy.Rate(1) robot_configuration = JointState() robot_configuration.header = Header() - robot_configuration.header.stamp = rospy.Time.now() - robot_configuration.name = [jointname] + robot_configuration.name = [joint_name] robot_configuration.position = [position] - robot_configuration.velocity = [] - robot_configuration.effort = [] + robot_configuration.velocity = [10] + robot_configuration.effort = [100] + while not rospy.is_shutdown(): + robot_configuration.header.stamp = rospy.Time.now() + rospy.loginfo(robot_configuration) + break pub1.publish(robot_configuration) - rate.sleep() + rospy.sleep(2) + if (choice == 2): + #rospy.Timer(rospy.Duration(2), joint_modifier) + rospy.Subscriber("joint_states", JointState, joint_callback) + #rospy.Timer(rospy.Duration(2), timer_callback) + rospy.spin() + if (choice == 3): + #rospy.Timer(rospy.Duration(2), joint_modifier) + rospy.Subscriber("/sr_tactile/touch/ff", Float64, tactile_callback) + #rospy.Timer(rospy.Duration(2), timer_callback_tactile) + rospy.spin() + + + + @@ -157,9 +115,9 @@ class Leg_attribute: r_3 = 3 # centre of gravity of links 3 from every leg i.e. distal link from distal joint radius = 0.5 #radius of the links global acc #acceleration at which the robot is supposed to move - j_angles = np.ones((1, 3)) # in radians - j_velocities = np.ones((1,3)) - j_efforts = np.ones((1, 3)) + j_angles = [] #np.ones((1, 3)) # in radians + j_velocities = [] #np.ones((1,3)) + j_efforts = [] #np.ones((1, 3)) #touch = False #variable to detect whether tactile sensor touch the ground or not def __init__(self, position1, position2, position3, velocity1, velocity2, velocity3, effort1, effort2, effort3, acceleration): self.j_angles[0] = position1 # vector containing the joint angles @@ -192,19 +150,10 @@ class Leg_attribute: def y_right_com(self, a, b, c, d, one_one, one_two, one_three, two_one, two_two, two_three, three_one, three_two, three_three, four_one, four_two, four_three, five_one, five_two, five_three, six_one, six_two, six_three, seven_one, seven_two, seven_three, eight_one, eight_two, eight_three): return (1/(2*(a+6*b)))*(3*a*d+2*b*c*(3*math.sin(two_three)+3*math.sin(four_three)+3*math.sin(six_three)+3*math.sin(eight_three)+2*math.sin(two_two)+2*math.sin(four_two)+2*math.sin(six_two)+2*math.sin(eight_two)+math.sin(two_one)+math.sin(four_one)+math.sin(six_one)+math.sin(eight_one))) - def x_system_com(self, a, b, c, d, one_one, one_two, one_three, two_one, two_two, two_three, three_one, three_two, - three_three, four_one, four_two, four_three, five_one, five_two, five_three, six_one, six_two, - six_three, seven_one, seven_two, seven_three, eight_one, eight_two, eight_three): - return (1/(a+6*b*c))*(2*a*d+b*c*(3*(math.cos(one_three) + math.cos(two_three) + math.cos(three_three) + - math.cos(four_three) + math.cos(five_three) + math.cos(six_three) + - math.cos(seven_three) + math.cos(eight_three)) + 2*(math.cos(one_two) + - math.cos(two_two) + math.cos(three_two) + math.cos(four_two) + - math.cos(five_two) + math.cos(six_two) + math.cos(seven_two) + - math.cos(eight_two)) + math.cos(one_one) + math.cos(two_one) + - math.cos(three_one) + math.cos(four_one) + math.cos(five_one) + - math.cos(six_one) + math.cos(seven_one) + math.cos(eight_one))) - - def y_system_com(self, a, b, c, d, one_one, one_two, one_three, two_one, two_two, two_three, three_one, three_two, three_three, four_onr, four_two, four_three, five_one, five_two, five_three, six_one, six_two, six_three, seven_one, seven_two, seven_three, eight_one, eight_two, eight_three): + def x_system_com(self, a, b, c, d, one_one, one_two, one_three, two_one, two_two, two_three, three_one, three_two, three_three, four_one, four_two, four_three, five_one, five_two, five_three, six_one, six_two, six_three, seven_one, seven_two, seven_three, eight_one, eight_two, eight_three): + return (1/(a+6*b*c))*(2*a*d+b*c*(3*(math.cos(one_three)+math.cos(two_three)+math.cos(three_three)+math.cos(four_three)+math.cos(five_three)+math.cos(six_three)+math.cos(seven_three)+math.cos(eight_three))+2*(math.cos(one_two)+math.cos(two_two)+math.cos(three_two)+math.cos(four_two)+math.cos(five_two)+math.cos(six_two)+math.cos(seven_two)+math.cos(eight_two))+math.cos(one_one)+math.cos(two_one)+math.cos(three_one)+math.cos(four_one)+math.cos(five_one)+math.cos(six_one)+math.cos(seven_one)+math.cos(eight_one))) + + def y_system_com(self, a, b, c, d, one_one, one_two, one_three, two_one, two_two, two_three, three_one, three_two, three_three, four_one, four_two, four_three, five_one, five_two, five_three, six_one, six_two, six_three, seven_one, seven_two, seven_three, eight_one, eight_two, eight_three): return (1/(a+6*b*c))*(2*a*d+b*c*(3*(math.sin(one_three)+math.sin(two_three)+math.sin(three_three)+math.sin(four_three)+math.sin(five_three)+math.sin(six_three)+math.sin(seven_three)+math.sin(eight_three))+2*(math.sin(one_two)+math.sin(two_two)+math.sin(three_two)+math.sin(four_two)+math.sin(five_two)+math.sin(six_two)+math.sin(seven_two)+math.sin(eight_two))+math.sin(one_one)+math.sin(two_one)+math.sin(three_one)+math.sin(four_one)+math.sin(five_one)+math.sin(six_one)+math.sin(seven_one)+math.sin(eight_one))) def mid_point_x(self, x_left, x_right): @@ -265,18 +214,18 @@ class Architecture: #global bias_o #global bias_h #global bias_h_c - self.neuron_i = tf.placeholder(tf.float32, shape=(neurons, 1)) # _input layer neurons - self.neuron_o = tf.placeholder(tf.float32, shape=(neurons, 1)) # output layer neurons - self.neuron_h = tf.placeholder(tf.float32, shape=(neurons/3, 1)) # hidden layer neurons, only 8 neurons because there are eight legs - self.neuron_h_c = tf.placeholder(tf.float32, shape=(neurons/3, 1)) # context layer neurons, only 8 neurons because there are eight in hidden layer - self.weights_i = tf.placeholder(tf.float32, shape=(neurons, layers)) # weights of input layer neurons - self.weights_o = tf.placeholder(tf.float32, shape=(neurons, layers)) # weights of output layer neurons - self.weights_h = tf.placeholder(tf.float32, shape=(neurons/3, layers)) # weights of hidden layer neurons - self.weights_h_c = tf.placeholder(tf.float32, shape=(neurons/3, layers)) # weights of context layer neurons + self.neuron_i = tf.compat.v1.placeholder(tf.float32, shape=(neurons, 1)) # _input layer neurons + self.neuron_o = tf.compat.v1.placeholder(tf.float32, shape=(neurons, 1)) # output layer neurons + self.neuron_h = tf.compat.v1.placeholder(tf.float32, shape=(neurons/3, 1)) # hidden layer neurons, only 8 neurons because there are eight legs + self.neuron_h_c = tf.compat.v1.placeholder(tf.float32, shape=(neurons/3, 1)) # context layer neurons, only 8 neurons because there are eight in hidden layer + self.weights_i = tf.compat.v1.placeholder(tf.float32, shape=(neurons, layers)) # weights of input layer neurons + self.weights_o = tf.compat.v1.placeholder(tf.float32, shape=(neurons, layers)) # weights of output layer neurons + self.weights_h = tf.compat.v1.placeholder(tf.float32, shape=(neurons/3, layers)) # weights of hidden layer neurons + self.weights_h_c = tf.compat.v1.placeholder(tf.float32, shape=(neurons/3, layers)) # weights of context layer neurons self.bias_i = tf.random_uniform((neurons, 1), minval = 0, maxval = 1, dtype = tf.float32, seed=9999) #biases of each neurons self.bias_o = tf.random_uniform((neurons, 1), minval = 0, maxval = 1, dtype = tf.float32, seed = 1111) - self.bias_h = tf.random_uniform((neurons/3, 1), minval = 0, maxval = 1, dtype = tf.float32, seed=2222) - self.bias_h_c = tf.random_uniform((neurons/3, 1), minval = 0, maxval = 1, dtype = tf.float32, seed=3333) + self.bias_h = tf.random_uniform((int(neurons/3), 1), minval = 0, maxval = 1, dtype = tf.float32, seed=2222) + self.bias_h_c = tf.random_uniform((8, 1), minval = 0, maxval = 1, dtype = tf.float32, seed=3333) def weight_initialize (self, neurons): weights1 = tf.Variable(tf.random_uniform((neurons, 1), minval=0, maxval=1, dtype=tf.float32, seed=7273)) @@ -294,8 +243,8 @@ class Architecture: return def input_method(self, neurons = [], weights = [], bias = []): - 'input function of the main neural network' - multi = tf.matmul(neurons, weights, transpose_a = tf.false, transpose_b=tf.false) + #input function of the main neural network + multi = tf.matmul(neurons, weights, transpose_a = False, transpose_b=False)#use False as tf.False if this does not work add1 = tf.add(multi, bias) ses = tf.Session() neuron_input = ses.run(add1) @@ -303,7 +252,7 @@ class Architecture: def transfer_function(self, a = []): b = tf.nn.softmax(a, name='sigmoid') - '0.5 being the threshold that is required to activate the neuron' + #0.5 being the threshold that is required to activate the neuron if (b >= 0.5): out = b*a else: @@ -311,20 +260,14 @@ class Architecture: return out def NN_learningPunishment(self, LearningRate, punishment): - 'a method to minimize the rewards and alot the weights based on that' - init1 = tf.global_variables_initializer() - with tf.Session as session1: - session1.run(init1) + #a method to minimize the rewards and alot the weights based on that optimizer = tf.train.GradientDescentOptimizer(LearningRate).minimize(punishment) with tf.Session as sess: sess.run(optimizer) return def NN_learningReward(self, LearningRate, reward): - 'a method to maximize reward and alot the weights based on that' - init1 = tf.global_variables_initializer() - with tf.Session as sess: - sess.run(init1) + #a method to maximize reward and alot the weights based on that optimizer = tf.train.GradientDescentOptimizer(LearningRate).minimize((-1*reward)) with tf.Session as session: session.run(optimizer) @@ -345,23 +288,32 @@ class MultiClassLogistic: self.neurons = neurons self.layers = layers global weight_in, weight_hid, weight_out, bias_hid, bias_in, bias_out - self.weight_in = weight_in - self.weight_hid = weight_hid - self.weight_out = weight_out - self.bias_hid = bias_hid - self.bias_out = bias_out - self.bias_in = bias_in - self.neuron_input = tf.placeholder(tf.float32, shape=(neurons, 1)) - self.neuron_hidden = tf.placeholder(tf.float32, shape=(neurons/4, 1)) - self.neuron_out = tf.placeholder(tf.float32, shape=(4, 1))#four neurons in output layer because of the four quadrants - weights1 = tf.Variable(tf.random_normal((neurons, 1), dtype=tf.float32, seed=1606))#weights of input layer - weights2 = tf.Variable(tf.random_normal((neurons/2, neurons/2), dtype=tf.float32, seed=1003))#weights for hidden layer, number of neurons in hidden layer is identified by the quadrant concept - weights3 = tf.Variable(tf.random_normal((4, 2), dtype=tf.float32, seed= 207))#weights for output layer + #self.weight_in = weight_in + #self.weight_hid = weight_hid + #self.weight_out = weight_out + #self.bias_hid = bias_hid + #self.bias_out = bias_out + #self.bias_in = bias_in + #self.neuron_input = tf.compat.v1.placeholder(tf.float32, shape=(neurons, 1)) + #self.neuron_hidden = tf.compat.v1.placeholder(tf.float32, shape=(neurons/4, 1)) + #self.neuron_out = tf.compat.v1.placeholder(tf.float32, shape=(4, 1))#four neurons in output layer because of the four quadrants + weight_in = tf.get_variable("weight_in", [neurons, 1]) + weight_hid = tf.get_variable("weight_hid", [int(neurons/2), int(neurons/2)]) + weight_out = tf.get_variable("weight_out", [4, 2]) + weights1 = np.random.rand(neurons, 1)#weights of input layer + weights2 = np.random.rand(int(neurons/2), int(neurons/2))#weights for hidden layer, number of neurons in hidden layer is identified by the quadrant concept + weights3 = np.random.rand(4, 2)#weights for output layer bias_in =tf.random_normal((neurons, 1), dtype = tf.float32, seed = 2009) - bias_hid = tf.random_normal((neurons/2, 1), dtype = tf.float32, seed = 2509) + bias_hid = tf.random_normal((int(neurons/2), 1), dtype = tf.float32, seed = 2509) bias_out = tf.random_normal((4, 1), dtype=tf.float32, seed = 1234) - sess = tf.Session() - weight_in, weight_hid, weight_out, bias_in, bias_hid, bias_out = sess.run(weights1, weights2, weights3, bias_in, bias_hid, bias_out) + with tf.Session() as session1: + session1.run(weight_in, feed_dict={weight_in:weights1}) + with tf.Session() as session2: + session2.run(weight_hid, feed_dict={weight_hid:weights2}) + with tf.Session() as session3: + session3.run(weight_out, feed_dict={weight_out:weights3}) + with tf.Session() as session4: + bias_in, bias_hid, bias_out =session4.run([bias_in, bias_hid, bias_out]) #defining input function that can accept the output from previous layer and can calculate the input for present layer @@ -390,9 +342,6 @@ class MultiClassLogistic: return b def kt_learning(self, learning_rate, n_out = [], n_preferred = []): 'where n_out is the actual output and n_preffered is the prefered output of the network' - init = tf.global_variables_initializer() - with tf.Session as session: - session.run(init) loss = tf.reduce_mean(tf.nn.softmax_cross_entropy_with_logits(labels=n_out, logits=n_preferred)) optimizer = tf.train.GradientDescentOptimizer(learning_rate).minimize(loss) with tf.Session() as sess: @@ -431,29 +380,35 @@ def normalization(a): return def one_hot_encoding( iteration_time, model_type): - a = np.zeros(4, 1) + a_1 = np.zeros((3, 1)) if (model_type == 1): - hot_encoded_matrix = np.insert(a, 0, 1, axis=0) + + hot_encoded_matrix = np.insert(a_1, 0, 1, axis=0)#insert 1 in the first coloumn in x axis elif(model_type == 2): - hot_encoded_matrix = np.insert(a, 1, 1, axis=0) + + hot_encoded_matrix = np.insert(a_1, 1, 1, axis=0) elif(model_type == 3): - hot_encoded_matrix = np.insert(a, 2, 1, axis=0) + + hot_encoded_matrix = np.insert(a_1, 2, 1, axis=0) elif(model_type == 4): - hot_encoded_matrix = np.insert(a, 3, 1, axis=0) + + hot_encoded_matrix = np.insert(a_1, 3, 1, axis=0) else: - print("please enter a valid model number") + raise ValueError(f"Value {model_type} is not a valid model number") return hot_encoded_matrix if __name__=="__main__": - spiderJoint1Names = ['spider::joint_1_1', 'spider::joint_1_2', 'spider::joint_1_3'] - spiderJoint2Names = ['spider::joint_2_1', 'spider::joint_2_2', 'spider::joint_2_3'] - spiderJoint3Names = ['spider::joint_3_1', 'spider::joint_3_2', 'spider::joint_3_3'] - spiderJoint4Names = ['spider::joint_4_1', 'spider::joint_4_2', 'spider::joint_4_3'] - spiderJoint5Names = ['spider::joint_5_1', 'spider::joint_5_2', 'spider::joint_5_3'] - spiderJoint6Names = ['spider::joint_6_1', 'spider::joint_6_2', 'spider::joint_6_3'] - spiderJoint7Names = ['spider::joint_7_1', 'spider::joint_7_2', 'spider::joint_7_3'] - spiderJoint8Names = ['spider::joint_8_1', 'spider::joint_8_2', 'spider::joint_8_3'] + spiderJoint1Names = ['joint_1_1', 'joint_1_2', 'joint_1_3'] + spiderJoint2Names = ['joint_2_1', 'joint_2_2', 'joint_2_3'] + spiderJoint3Names = ['joint_3_1', 'joint_3_2', 'joint_3_3'] + spiderJoint4Names = ['joint_4_1', 'joint_4_2', 'joint_4_3'] + spiderJoint5Names = ['joint_5_1', 'joint_5_2', 'joint_5_3'] + spiderJoint6Names = ['joint_6_1', 'joint_6_2', 'joint_6_3'] + spiderJoint7Names = ['joint_7_1', 'joint_7_2', 'joint_7_3'] + spiderJoint8Names = ['joint_8_1', 'joint_8_2', 'joint_8_3'] + with tf.Session() as se1: + se1.run(tf.global_variables_initializer()) model_1 = Architecture(3, 24) #for model one of the terrain model_2 = Architecture(3, 24) #for model two of the terrain model_3 = Architecture(3, 24) #for model three of the terrain @@ -469,88 +424,86 @@ if __name__=="__main__": global run_time global model_trained run_time_time = input("please enter how long you intend to run the robot") - 'giving initial angles ' - initial_angles = np.random.randint(0, 3014, size=24) + #'giving initial angles ' + initial_angles = np.random.uniform(low = 0, high =2.5, size=24) number = 0 - for spiderJoint1Name in spiderJoint1Names: - talker(spiderJoint1Name, initial_angles[number]) + length1 = len(spiderJoint1Names) + length2 = len(spiderJoint2Names) + length3 = len(spiderJoint3Names) + length4 = len(spiderJoint4Names) + length5 = len(spiderJoint5Names) + length6 = len(spiderJoint6Names) + length7 = len(spiderJoint7Names) + length8 = len(spiderJoint8Names) + for i1 in range(length1): + jointname = spiderJoint1Names[i1] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint2Name in spiderJoint2Names: - talker(spiderJoint2Name, initial_angles[number]) + print(number) + for i2 in range(length2): + jointname = spiderJoint2Names[i2] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint3Name in spiderJoint3Names: - talker(spiderJoint3Name, initial_angles[number]) + for i3 in range(length3): + jointname = spiderJoint3Names[i3] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint4Name in spiderJoint4Names: - talker(spiderJoint4Name, initial_angles[number]) + for i4 in range(length4): + jointname = spiderJoint4Names[i4] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint5Name in spiderJoint5Names: - talker(spiderJoint5Name, initial_angles[number]) + for i5 in range(length5): + jointname = spiderJoint5Names[i5] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint6Name in spiderJoint6Names: - talker(spiderJoint6Name, initial_angles[number]) + for i6 in range(length6): + jointname = spiderJoint6Names[i6] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint7Name in spiderJoint7Names: - talker(spiderJoint7Name, initial_angles[number]) + for i7 in range(length7): + jointname = spiderJoint7Names[i7] + joint_modifier(1, jointname, initial_angles[number]) number+=1 - for spiderJoint8Name in spiderJoint8Names: - talker(spiderJoint8Name, initial_angles[number]) + for i8 in range(length8): + jointname = spiderJoint8Names[i8] + joint_modifier(1, jointname, initial_angles[number]) number+=1 + print("succefully published initial angles") + joint_modifier(3)#just checking whether tactile callback is working or not + print("printing tactile states") + print(tactile_states)#debugging tactile callback + print("printed tactile states") if ( run_method == 'train'): training_time = input("please enter how long you intend to train the algorithm") run_time = training_time - model_trained = input("which model do you want to train ?, please enter model_number for straight terrain select 1, for accute angled terrain select 2, for obtuse angled terrain select 3, for up/down terrain select 4") + model_trained = int(input("which model do you want to train ?, please enter model_number for straight terrain select 1, for accute angled terrain select 2, for obtuse angled terrain select 3, for up/down terrain select 4")) output = one_hot_encoding(run_time, model_trained) pref_out = tf.placeholder(tf.float32, shape=(4, 1)) - with tf.Session as sess1: + with tf.Session() as sess1: sess1.run(pref_out, feed_dict={pref_out: output}) + print("bug finding") + i=0 + position = np.array(3) + velocity = np.array(3) + effort = np.array(3) while(run_time): - for spiderJoint1Name in spiderJoint1Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint1Name) - leg_1 = Leg_attribute(position, velocity, effort) - for spiderJoint2Name in spiderJoint2Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint2Name) - leg_2 = Leg_attribute(position, velocity, effort) - for spiderJoint3Name in spiderJoint3Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint3Name) - leg_3 = Leg_attribute(position, velocity, effort) - for spiderJoint4Name in spiderJoint4Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint4Name) - leg_4 = Leg_attribute(position, velocity, effort) - for spiderJoint5Name in spiderJoint5Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint5Name) - leg_5 = Leg_attribute(position, velocity, effort) - for spiderJoint6Name in spiderJoint6Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint6Name) - leg_6 = Leg_attribute(position, velocity, effort) - for spiderJoint7Name in spiderJoint7Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint7Name) - leg_7 = Leg_attribute(position, velocity, effort) - for spiderJoint8Name in spiderJoint8Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint8Name) - leg_8 = Leg_attribute(position, velocity, effort) - (tactile_1, tactile_2, tactile_3, tactile_4, tactie_5, tactile_6, tactile_7, tactile_8) = listener() + joint_modifier(2) + print("printing g_position") + print(g_position)#to check the format of g_position + print("printed g _position") + leg_1 = Leg_attribute(g_position[0], g_position[1], g_position[2], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_2 = Leg_attribute(g_position[3], g_position[4], g_position[5], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_3 = Leg_attribute(g_position[6], g_position[7], g_position[8], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_4 = Leg_attribute(g_position[9], g_position[10], g_position[11], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_5 = Leg_attribute(g_position[12], g_position[13], g_position[14], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_6 = Leg_attribute(g_position[15], g_position[16], g_position[17], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_7 = Leg_attribute(g_position[18], g_position[19], g_position[20], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_8 = Leg_attribute(g_position[21], g_position[22], g_position[23], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + (tactile_1, tactile_2, tactile_3, tactile_4, tactie_5, tactile_6, tactile_7, tactile_8) = joint_modifier(3) + print("not_touch") not_touch = 0 balance_punishment = 0 - if(tactile_1==0.0): - not_touch +=1 - elif(tactile_2==0.0): - not_touch+=1 - elif(tactile_3==0.0): - not_touch+=1 - elif(tactile_3==0.0): - not_touch+=1 - elif(tactile_4==0.0): - not_touch+=1 - elif(tactile_5==0.0): - not_touch+=1 - elif(tactile_6==0.0): - not_touch+=1 - elif(tactile_7==0.0): - not_touch+=1 - elif(tactile_8==0.0): - not_touch+=1 - if(not_touch>5): + if(not_touch<3): balance_punishment = 5 joint_angle_leg_1 = leg_1.give_angles() joint_angle_leg_2 = leg_2.give_angles() @@ -589,30 +542,30 @@ if __name__=="__main__": model_1.get_neuron_value(model_1.neuron_o, input_layerout) output_layerout = model_1.output_function(model_1.neuron_o) # output of the neural network for model 1 that is to try: - talker('spider::joint_1_1', output_layerout[0]) - talker('spider::joint_1_2', output_layerout[1]) - talker('spider::joint_1_3', output_layerout[2]) - talker('spider::joint_4_1', output_layerout[9]) - talker('spider::joint_4_2', output_layerout[10]) - talker('spider::joint_4_3', output_layerout[11]) - talker('spider::joint_5_1', output_layerout[12]) - talker('spider::joint_5_2', output_layerout[13]) - talker('spider::joint_5_3', output_layerout[14]) - talker('spider::joint_8_1', output_layerout[21]) - talker('spider::joint_8_2', output_layerout[22]) - talker('spider::joint_8_3', output_layerout[23]) - talker('spider::joint_2_1', output_layerout[3]) - talker('spider::joint_2_2', output_layerout[4]) - talker('spider::joint_2_3', output_layerout[5]) - talker('spider::joint_3_1', output_layerout[6]) - talker('spider::joint_3_2', output_layerout[7]) - talker('spider::joint_3_3', output_layerout[8]) - talker('spider::joint_6_1', output_layerout[15]) - talker('spider::joint_6_2', output_layerout[16]) - talker('spider::joint_6_3', output_layerout[17]) - talker('spider::joint_7_1', output_layerout[18]) - talker('spider::joint_7_2', output_layerout[19]) - talker('spider::joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) except rospy.ROSInterruptException: pass rospy.spin() @@ -636,30 +589,30 @@ if __name__=="__main__": model_2.get_neuron_value(model_2.neuron_o, input_layerout) output_layerout = model_2.output_function(model_2.neuron_o) # output of the neural network for model 1 try: - talker('spider::joint_7_1', output_layerout[18]) - talker('spider::joint_7_2', output_layerout[19]) - talker('spider::joint_7_3', output_layerout[20]) - talker('spider::joint_2_1', output_layerout[3]) - talker('spider::joint_2_2', output_layerout[4]) - talker('spider::joint_2_3', output_layerout[5]) - talker('spider::joint_1_1', output_layerout[0]) - talker('spider::joint_1_2', output_layerout[1]) - talker('spider::joint_1_3', output_layerout[2]) - talker('spider::joint_4_1', output_layerout[9]) - talker('spider::joint_4_2', output_layerout[10]) - talker('spider::joint_4_3', output_layerout[11]) - talker('spider::joint_3_1', output_layerout[6]) - talker('spider::joint_3_2', output_layerout[7]) - talker('spider::joint_3_3', output_layerout[8]) - talker('spider::joint_6_1', output_layerout[15]) - talker('spider::joint_6_2', output_layerout[16]) - talker('spider::joint_6_3', output_layerout[17]) - talker('spider::joint_5_1', output_layerout[12]) - talker('spider::joint_5_2', output_layerout[13]) - talker('spider::joint_5_3', output_layerout[14]) - talker('spider::joint_8_1', output_layerout[21]) - talker('spider::joint_8_2', output_layerout[22]) - talker('spider::joint_8_3', output_layerout[23]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) except rospy.ROSInterruptException: pass rospy.spin() @@ -683,30 +636,30 @@ if __name__=="__main__": model_3.get_neuron_value(model_3.neuron_o, input_layerout) output_layerout = model_3.output_function(model_3.neuron_o) # output of the neural network for model 1 try: - talker('spider::joint_1_1', output_layerout[0]) - talker('spider::joint_1_2', output_layerout[1]) - talker('spider::joint_1_3', output_layerout[2]) - talker('spider::joint_8_1', output_layerout[21]) - talker('spider::joint_8_2', output_layerout[22]) - talker('spider::joint_8_3', output_layerout[23]) - talker('spider::joint_3_1', output_layerout[6]) - talker('spider::joint_3_2', output_layerout[7]) - talker('spider::joint_3_3', output_layerout[8]) - talker('spider::joint_2_1', output_layerout[3]) - talker('spider::joint_2_2', output_layerout[4]) - talker('spider::joint_2_3', output_layerout[5]) - talker('spider::joint_5_1', output_layerout[12]) - talker('spider::joint_5_2', output_layerout[13]) - talker('spider::joint_5_3', output_layerout[14]) - talker('spider::joint_4_1', output_layerout[9]) - talker('spider::joint_4_2', output_layerout[10]) - talker('spider::joint_4_3', output_layerout[11]) - talker('spider::joint_7_1', output_layerout[18]) - talker('spider::joint_7_2', output_layerout[19]) - talker('spider::joint_7_3', output_layerout[20]) - talker('spider::joint_6_1', output_layerout[15]) - talker('spider::joint_6_2', output_layerout[16]) - talker('spider::joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) except rospy.ROSInterruptException: pass rospy.spin() @@ -730,30 +683,30 @@ if __name__=="__main__": model_4.get_neuron_value(model_4.neuron_o, input_layerout) output_layerout = model_4.output_function(model_4.neuron_o) # output of the neural network for model 1 try: - talker('spider::joint_1_1', output_layerout[0]) - talker('spider::joint_1_2', output_layerout[1]) - talker('spider::joint_1_3', output_layerout[2]) - talker('spider::joint_3_1', output_layerout[6]) - talker('spider::joint_3_2', output_layerout[7]) - talker('spider::joint_3_3', output_layerout[8]) - talker('spider::joint_5_1', output_layerout[12]) - talker('spider::joint_5_2', output_layerout[13]) - talker('spider::joint_5_3', output_layerout[14]) - talker('spider::joint_7_1', output_layerout[18]) - talker('spider::joint_7_2', output_layerout[19]) - talker('spider::joint_7_3', output_layerout[20]) - talker('spider::joint_2_1', output_layerout[3]) - talker('spider::joint_2_2', output_layerout[4]) - talker('spider::joint_2_3', output_layerout[5]) - talker('spider::joint_4_1', output_layerout[9]) - talker('spider::joint_4_2', output_layerout[10]) - talker('spider::joint_4_3', output_layerout[11]) - talker('spider::joint_6_1', output_layerout[15]) - talker('spider::joint_6_2', output_layerout[16]) - talker('spider::joint_6_3', output_layerout[17]) - talker('spider::joint_8_1', output_layerout[21]) - talker('spider::joint_8_2', output_layerout[22]) - talker('spider::joint_8_3', output_layerout[23]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) except rospy.ROSInterruptException: pass rospy.spin() @@ -860,42 +813,20 @@ if __name__=="__main__": run_time = 1 rospy.spin() joint_angles_input = np.array(24) - output_layerhidcont = np.zeros(8, 1) + output_layerhidcont = np.zeros((8, 1)) + joint_modifier(2) while run_time: - for spiderJoint1Name in spiderJoint1Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint1Name) - leg1 = Leg_attribute(position, velocity, effort) - - for spiderJoint2Name in spiderJoint2Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint2Name) - leg2 = Leg_attribute(position, velocity, effort) - - for spiderJoint3Name in spiderJoint3Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint3Name) - leg3 = Leg_attribute(position, velocity, effort) - - for spiderJoint4Name in spiderJoint4Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint4Name) - leg4 = Leg_attribute(position, velocity, effort) - - for spiderJoint5Name in spiderJoint5Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint5Name) - leg5 = Leg_attribute(position, velocity, effort) - - for spiderJoint6Name in spiderJoint6Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint6Name) - leg6 = Leg_attribute(position, velocity, effort) - - for spiderJoint7Name in spiderJoint7Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint7Name) - leg7 = Leg_attribute(position, velocity, effort) - - for spiderJoint8Name in spiderJoint8Names: - (position, velocity, effort) = call_return_joint_states(spiderJoint8Name) - leg8 = Leg_attribute(position, velocity, effort) + leg_1 = Leg_attribute(g_position[0], g_position[1], g_position[2], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_2 = Leg_attribute(g_position[3], g_position[4], g_position[5], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_3 = Leg_attribute(g_position[6], g_position[7], g_position[8], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_4 = Leg_attribute(g_position[9], g_position[10], g_position[11], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_5 = Leg_attribute(g_position[12], g_position[13], g_position[14], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_6 = Leg_attribute(g_position[15], g_position[16], g_position[17], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_7 = Leg_attribute(g_position[18], g_position[19], g_position[20], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) + leg_8 = Leg_attribute(g_position[21], g_position[22], g_position[23], velocity1 = 10, velocity2 = 10, velocity3 = 10, effort1 = 100, effort2 = 100, effort3 = 100, acceleration=1) - (tactile_1, tactile_2, tactile_3, tactile_4, tactile_5, tactile_6, tactile_7, tactile_8) = listener() + (tactile_1, tactile_2, tactile_3, tactile_4, tactile_5, tactile_6, tactile_7, tactile_8) = joint_modifier(3) not_touch = 0 balance_punishment = 0 if (tactile_1 == 0.0): @@ -1043,30 +974,30 @@ if __name__=="__main__": model = max(softmax_output) if (softmax_output[0] == model): try: - talker('spider::joint_1_1', output_layerout1[0]) - talker('spider::joint_1_2', output_layerout1[1]) - talker('spider::joint_1_3', output_layerout1[2]) - talker('spider::joint_4_1', output_layerout1[9]) - talker('spider::joint_4_2', output_layerout1[10]) - talker('spider::joint_4_3', output_layerout1[11]) - talker('spider::joint_5_1', output_layerout1[12]) - talker('spider::joint_5_2', output_layerout1[13]) - talker('spider::joint_5_3', output_layerout1[14]) - talker('spider::joint_8_1', output_layerout1[21]) - talker('spider::joint_8_2', output_layerout1[22]) - talker('spider::joint_8_3', output_layerout1[23]) - talker('spider::joint_2_1', output_layerout1[3]) - talker('spider::joint_2_2', output_layerout1[4]) - talker('spider::joint_2_3', output_layerout1[5]) - talker('spider::joint_3_1', output_layerout1[6]) - talker('spider::joint_3_2', output_layerout1[7]) - talker('spider::joint_3_3', output_layerout1[8]) - talker('spider::joint_6_1', output_layerout1[15]) - talker('spider::joint_6_2', output_layerout1[16]) - talker('spider::joint_6_3', output_layerout1[17]) - talker('spider::joint_7_1', output_layerout1[18]) - talker('spider::joint_7_2', output_layerout1[19]) - talker('spider::joint_7_3', output_layerout1[20]) + joint_modifier(1, 'joint_1_1', output_layerout1[0]) + joint_modifier(1, 'joint_1_2', output_layerout1[1]) + joint_modifier(1, 'joint_1_3', output_layerout1[2]) + joint_modifier(1, 'joint_4_1', output_layerout1[9]) + joint_modifier(1, 'joint_4_2', output_layerout1[10]) + joint_modifier(1, 'joint_4_3', output_layerout1[11]) + joint_modifier(1, 'joint_5_1', output_layerout1[12]) + joint_modifier(1, 'joint_5_2', output_layerout1[13]) + joint_modifier(1, 'joint_5_3', output_layerout1[14]) + joint_modifier(1, 'joint_8_1', output_layerout1[21]) + joint_modifier(1, 'joint_8_2', output_layerout1[22]) + joint_modifier(1, 'joint_8_3', output_layerout1[23]) + joint_modifier(1, 'joint_2_1', output_layerout1[3]) + joint_modifier(1, 'joint_2_2', output_layerout1[4]) + joint_modifier(1, 'joint_2_3', output_layerout1[5]) + joint_modifier(1, 'joint_3_1', output_layerout1[6]) + joint_modifier(1, 'joint_3_2', output_layerout1[7]) + joint_modifier(1, 'joint_3_3', output_layerout1[8]) + joint_modifier(1, 'joint_6_1', output_layerout1[15]) + joint_modifier(1, 'joint_6_2', output_layerout1[16]) + joint_modifier(1, 'joint_6_3', output_layerout1[17]) + joint_modifier(1, 'joint_7_1', output_layerout1[18]) + joint_modifier(1, 'joint_7_2', output_layerout1[19]) + joint_modifier(1, 'joint_7_3', output_layerout1[20]) x_left_com = Leg_attribute.x_left_com(leg1.m_l, g, leg1.r_1, leg1.l_1, output_layerout1[0], output_layerout1[1], output_layerout1[2], output_layerout1[3], output_layerout1[4], output_layerout1[5], output_layerout1[6], @@ -1145,30 +1076,30 @@ if __name__=="__main__": rospy.spin() elif (softmax_output[1] == model): try: - talker('spider::joint_7_1', output_layerout2[18]) - talker('spider::joint_7_2', output_layerout2[19]) - talker('spider::joint_7_3', output_layerout2[20]) - talker('spider::joint_2_1', output_layerout2[3]) - talker('spider::joint_2_2', output_layerout2[4]) - talker('spider::joint_2_3', output_layerout2[5]) - talker('spider::joint_1_1', output_layerout2[0]) - talker('spider::joint_1_2', output_layerout2[1]) - talker('spider::joint_1_3', output_layerout2[2]) - talker('spider::joint_4_1', output_layerout2[9]) - talker('spider::joint_4_2', output_layerout2[10]) - talker('spider::joint_4_3', output_layerout2[11]) - talker('spider::joint_3_1', output_layerout2[6]) - talker('spider::joint_3_2', output_layerout2[7]) - talker('spider::joint_3_3', output_layerout2[8]) - talker('spider::joint_6_1', output_layerout2[15]) - talker('spider::joint_6_2', output_layerout2[16]) - talker('spider::joint_6_3', output_layerout2[17]) - talker('spider::joint_5_1', output_layerout2[12]) - talker('spider::joint_5_2', output_layerout2[13]) - talker('spider::joint_5_3', output_layerout2[14]) - talker('spider::joint_8_1', output_layerout2[21]) - talker('spider::joint_8_2', output_layerout2[22]) - talker('spider::joint_8_3', output_layerout2[23]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) x_left_com = Leg_attribute.x_left_com(leg1.m_l, g, leg1.r_1, leg1.l_1, output_layerout2[0], output_layerout2[1], output_layerout2[2], output_layerout2[3], output_layerout2[4], output_layerout2[5], output_layerout2[6], @@ -1247,30 +1178,30 @@ if __name__=="__main__": rospy.spin() elif (softmax_output[2] == model): try: - talker('spider::joint_1_1', output_layerout3[0]) - talker('spider::joint_1_2', output_layerout3[1]) - talker('spider::joint_1_3', output_layerout3[2]) - talker('spider::joint_8_1', output_layerout3[21]) - talker('spider::joint_8_2', output_layerout3[22]) - talker('spider::joint_8_3', output_layerout3[23]) - talker('spider::joint_3_1', output_layerout3[6]) - talker('spider::joint_3_2', output_layerout3[7]) - talker('spider::joint_3_3', output_layerout3[8]) - talker('spider::joint_2_1', output_layerout3[3]) - talker('spider::joint_2_2', output_layerout3[4]) - talker('spider::joint_2_3', output_layerout3[5]) - talker('spider::joint_5_1', output_layerout3[12]) - talker('spider::joint_5_2', output_layerout3[13]) - talker('spider::joint_5_3', output_layerout3[14]) - talker('spider::joint_4_1', output_layerout3[9]) - talker('spider::joint_4_2', output_layerout3[10]) - talker('spider::joint_4_3', output_layerout3[11]) - talker('spider::joint_7_1', output_layerout3[18]) - talker('spider::joint_7_2', output_layerout3[19]) - talker('spider::joint_7_3', output_layerout3[20]) - talker('spider::joint_6_1', output_layerout3[15]) - talker('spider::joint_6_2', output_layerout3[16]) - talker('spider::joint_6_3', output_layerout3[17]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) x_left_com = Leg_attribute.x_left_com(leg1.m_l, g, leg1.r_1, leg1.l_1, output_layerout3[0], output_layerout3[1], output_layerout3[2], output_layerout3[3], output_layerout3[4], output_layerout3[5], output_layerout3[6], @@ -1345,30 +1276,30 @@ if __name__=="__main__": rospy.spin() elif (softmax_output[3] == model): try: - talker('spider::joint_1_1', output_layerout4[0]) - talker('spider::joint_1_2', output_layerout4[1]) - talker('spider::joint_1_3', output_layerout4[2]) - talker('spider::joint_3_1', output_layerout4[6]) - talker('spider::joint_3_2', output_layerout4[7]) - talker('spider::joint_3_3', output_layerout4[8]) - talker('spider::joint_5_1', output_layerout4[12]) - talker('spider::joint_5_2', output_layerout4[13]) - talker('spider::joint_5_3', output_layerout4[14]) - talker('spider::joint_7_1', output_layerout4[18]) - talker('spider::joint_7_2', output_layerout4[19]) - talker('spider::joint_7_3', output_layerout4[20]) - talker('spider::joint_2_1', output_layerout4[3]) - talker('spider::joint_2_2', output_layerout4[4]) - talker('spider::joint_2_3', output_layerout4[5]) - talker('spider::joint_4_1', output_layerout4[9]) - talker('spider::joint_4_2', output_layerout4[10]) - talker('spider::joint_4_3', output_layerout4[11]) - talker('spider::joint_6_1', output_layerout4[15]) - talker('spider::joint_6_2', output_layerout4[16]) - talker('spider::joint_6_3', output_layerout4[17]) - talker('spider::joint_8_1', output_layerout4[21]) - talker('spider::joint_8_2', output_layerout4[22]) - talker('spider::joint_8_3', output_layerout4[23]) + joint_modifier(1, 'joint_1_1', output_layerout[0]) + joint_modifier(1, 'joint_1_2', output_layerout[1]) + joint_modifier(1, 'joint_1_3', output_layerout[2]) + joint_modifier(1, 'joint_3_1', output_layerout[6]) + joint_modifier(1, 'joint_3_2', output_layerout[7]) + joint_modifier(1, 'joint_3_3', output_layerout[8]) + joint_modifier(1, 'joint_5_1', output_layerout[12]) + joint_modifier(1, 'joint_5_2', output_layerout[13]) + joint_modifier(1, 'joint_5_3', output_layerout[14]) + joint_modifier(1, 'joint_7_1', output_layerout[18]) + joint_modifier(1, 'joint_7_2', output_layerout[19]) + joint_modifier(1, 'joint_7_3', output_layerout[20]) + joint_modifier(1, 'joint_2_1', output_layerout[3]) + joint_modifier(1, 'joint_2_2', output_layerout[4]) + joint_modifier(1, 'joint_2_3', output_layerout[5]) + joint_modifier(1, 'joint_4_1', output_layerout[9]) + joint_modifier(1, 'joint_4_2', output_layerout[10]) + joint_modifier(1, 'joint_4_3', output_layerout[11]) + joint_modifier(1, 'joint_6_1', output_layerout[15]) + joint_modifier(1, 'joint_6_2', output_layerout[16]) + joint_modifier(1, 'joint_6_3', output_layerout[17]) + joint_modifier(1, 'joint_8_1', output_layerout[21]) + joint_modifier(1, 'joint_8_2', output_layerout[22]) + joint_modifier(1, 'joint_8_3', output_layerout[23]) x_left_com = Leg_attribute.x_left_com(leg1.m_l, g, leg1.r_1, leg1.l_1, output_layerout4[0], output_layerout4[1], output_layerout4[2], output_layerout4[3], output_layerout4[4], output_layerout4[5], output_layerout4[6], diff --git a/spider_control/control1.py b/spider_control/control1.py new file mode 100755 index 0000000000000000000000000000000000000000..b7d1d6085a72cebf3b11967bbdaf7bf37e5872b3 --- /dev/null +++ b/spider_control/control1.py @@ -0,0 +1,175 @@ +#!/usr/bin/python3 +#from my_network import Architecture +import my_network as nn +import leg_dynamics as ld +import knowledge_transfer as kt +import tensorflow as tf +import numpy as np +import roslib +roslib.load_manifest('spider_control') +from matplotlib import pyplot +#import pyplot as plt +from geometry_msgs import * +import rospy, yaml, sys +#from osrf_msgs.msg import JointCommands +from sensor_msgs.msg import JointState +#from joint_states_listener.srv import * +#from joint_States_listener.srv import ReturnJointStates +import threading +import time +from std_msgs.msg import Float64 +from std_msgs.msg import Header +from sklearn.multiclass import OneVsRestClassifier +from sklearn.svm import LinearSVC +import csv +import os.path +import json +import _pickle as pickle + + + + +g_joint_states = None +g_positions = None +g_pos1 = None +#tactile_output = None + + + +def tactile_callback(msg): + global tactile_output + tactile_output = msg.data + leg.update_tactile(tactile_output) + +def joint_callback(data, args): + global g_positions + global g_joint_states + global g_pos1 + global new_position + global knowledge_dict + global main_dict + main_dict = {} + knowledge_dict = {} + simulation_mode = args[0] #to distinguish between training and testing + model_number = args[1]#to distiguish between the type of model to train incase of training + rospy.loginfo(data.position)#testing + pub_msg = JointState() # Make a new msg to publish results + pub_msg.header = Header() + pub_msg.name = data.name + pub_msg.velocity = [10] * len(data.name) + pub_msg.effort = [100] * len(data.name) + g_positions = data.position + velocity = 10*len(data.name) + effort = 10*len(data.name) + carollis_inp = leg.carollis_input() + print("carollis input is ")#testing + print(carollis_inp) + knowledge_out, out_tensor, knowledge_dict = knowledge.run(carollis_inp) + model_num = np.where(knowledge_out == np.amax(knowledge_out)) + reward = leg.leg_run() + if(simulation_mode == 'test'): + if(model_num == 0 ): + new_position, main_dict = model1.nn_run(g_positions) + print("printing new position") + print(new_position)#debuggings + pub_msg.position = new_position + elif(model_num == 1): + print("printing new position") + new_position, main_dict = model2.nn_run(g_positions) + print(new_position)#debugging + pub_msg.position = new_position + elif(model_num == 2): + print("printing new position") + new_position, main_dict = model3.nn_run(g_positions) + print(new_position)#degingbug + pub_msg.position = new_position + elif(model_num == 3): + new_position, main_dict = model4.nn_run(g_positions) + print("printing new position") + print(new_position)#debugging + pub_msg.position = new_position + leg.update_angles(new_position) + leg.update_effort(effort) + leg.update_velocity(velocity) + joint_pub.publish(pub_msg) + elif(simulation_mode == 'train'): + ou = tf.one_hot([model_number-1], 4) + knowledge.learn(out_tensor, ou) + if(model_number == 1): + print("printing new position") + new_position, main_dict = model1.nn_run(g_positions) + print(new_position)#debugging + pub_msg.position = new_position + elif(model_number == 2): + print("printing new position") + new_position, main_dict = model2.nn_run(g_positions) + print(new_position)#debugging + pub_msg.position = new_position + elif(model_number == 3): + print("printing new position") + new_position, main_dict = model3.nn_run(g_positions) + print(new_position)#debugging + pub_msg.position = new_position + elif(model_number == 4): + print("printing new position") + new_position, main_dict = model4.nn_run(g_positions) + print(new_position)#debugging + pub_msg.position = new_position + leg.update_angles(new_position) + leg.update_effort(effort) + leg.update_velocity(velocity) + joint_pub.publish(pub_msg) + +if __name__=='__main__': + global variables_list_main + global variables_list_kt + global variables_list_m + graph1 = tf.Graph() + with graph1.as_default(): + model1 = nn.Architecture(4, 24, 1) + graph2 = tf.Graph() + with graph2.as_default(): + model2 = nn.Architecture(4, 24, 2) + graph3 = tf.Graph() + with graph3.as_default(): + model3 = nn.Architecture(4, 24, 3) + graph4 = tf.Graph() + with graph4.as_default(): + model4 = nn.Architecture(4, 24, 4) + graph5 = tf.Graph() + with graph5.as_default(): + knowledge = kt.MultiClassLogistic(8, 3) + #if(os.path.isfile('main_network.csv') == True): + # try: + # f2.open('main_network.csv') + # except IOError: + # print('file is not accessible') + + pos = np.random.uniform(low = 0, high =2.5, size=24) + vel = 10 + eff = 100 + tact = np.zeros(8) + leg = ld.Leg_attribute(pos, vel, eff, tact) + mode = input('please enter whether you want to test or train ?') + if(mode == 'train'): + model_number = int(input('please enter the model you wish to train i.e. 1, 2, 3, 4 \n ')) + rospy.init_node('joint_logger_node', anonymous = True) + rospy.Subscriber("/sr_tactile/touch/ff", Float64, tactile_callback) + rospy.Subscriber("joint_states", JointState, joint_callback, (mode, model_number)) + joint_pub = rospy.Publisher('target_joint_states', JointState, queue_size = 10) + rospy.spin() + print("writing csv file") + for key in knowledge_dict.keys(): + print("%s,%s\n"%(key,knowledge_dict[key])) + w = csv.writer(open("weights.csv", "w")) + for key, val in knowledge_dict.items(): + w.writerow([key, val]) + else: + rospy.init_node('jint_logger_node', anonymous=True) + rospy.Subscriber("/sr_tactile/touch/ff", Float64, tactile_callback) + rospy.Subscriber("joint_states", JointState, joint_callback, (mode)) + joint_pub = rospy.Publisher('target_joint_states', JointState, queue_size = 10) + rospy.spin() + + + diff --git a/spider_control/credentials.json b/spider_control/credentials.json new file mode 100644 index 0000000000000000000000000000000000000000..eb5abe1e1051958c4b034093db3152cedeaa44ad --- /dev/null +++ b/spider_control/credentials.json @@ -0,0 +1 @@ +{"installed":{"client_id":"511783950556-un9l2bprje048plm2vt1kst3c85ftuda.apps.googleusercontent.com","project_id":"quickstart-1565727349816","auth_uri":"https://accounts.google.com/o/oauth2/auth","token_uri":"https://oauth2.googleapis.com/token","auth_provider_x509_cert_url":"https://www.googleapis.com/oauth2/v1/certs","client_secret":"-_XzoTD1eMSnNF2IP8VR9PTr","redirect_uris":["urn:ietf:wg:oauth:2.0:oob","http://localhost"]}} \ No newline at end of file diff --git a/spider_control/knowledge_transfer.py b/spider_control/knowledge_transfer.py new file mode 100755 index 0000000000000000000000000000000000000000..b025d04bc347220313f3367e8b5e6e0fa3a7058f --- /dev/null +++ b/spider_control/knowledge_transfer.py @@ -0,0 +1,161 @@ +#!/usr/bin/python3 +import tensorflow as tf +import numpy as np +from matplotlib import pyplot +#import pyplot as plt +import math +import time +from sklearn.preprocessing import normalize + +class MultiClassLogistic: + + def __init__(self, neurons, layers): + self.neurons = neurons + self.layers = layers + self.weight_initer = tf.compat.v1.truncated_normal_initializer(mean=0.0, stddev=0.01) + self.weight_initer1 = tf.compat.v1.truncated_normal_initializer(mean=1.0, stddev=0.01) + self.weight_initer2 = tf.compat.v1.truncated_normal_initializer(mean=2.0, stddev=0.01) + self.bias_initer =tf.compat.v1.truncated_normal_initializer(mean=0.1, stddev=0.01) + self.bias_initer1 =tf.compat.v1.truncated_normal_initializer(mean=0.2, stddev=0.01) + self.bias_initer2 =tf.compat.v1.truncated_normal_initializer(mean=0.3, stddev=0.01) + + + #defining input function that can accept the output from previous layer and can calculate the input for present layer + + def input_function(self, a = [], b = [], c = []): + 'where b=output value of neurons from previous layer, a = weights of neurons from the present layer, c = bias' + multiplication = tf.multiply(a, b) + add = tf.add(multiplication, c) + sess = tf.Session() + n_input = sess.run(add) + return n_input + #function that returns the softmax of the output layer or any given array of neurons + def out_softmax(self, neuron_out): + output = tf.nn.softmax(neuron_out) + with tf.Session() as sess: + out = sess.run(output) + return out + + def kt_learning(self, learning_rate, n_out , n_preferred): + 'where n_out is the actual output and n_preffered is the prefered output of the network' + loss = tf.reduce_mean(tf.nn.softmax_cross_entropy_with_logits(labels=n_out, logits=n_preferred)) + optimizer = tf.train.GradientDescentOptimizer(learning_rate).minimize(loss) + init_l = tf.compat.v1.global_variables_initializer() + with tf.Session() as sess: + sess.run(init_l) + sess.run(optimizer) + def normalization(self, inputs): + a_min = min(inputs) + a_max = max(inputs) + for i in range(len(inputs)): + inputs[i] = (inputs[i]-a_min)/(a_max-a_min) + + def get_var_list(self): + ls = tf.trainable_variables() + ii = tf.global_variables_initializer() + with tf.Session() as sessio: + sessio.run(ii) + l = sessio.run(ls) + return l, ls + + + def run(self, carollis_input): + k_dict = {} + c_in=normalize(carollis_input, axis = 0) + print('normalized carollis input is \n') + print(c_in) + c_in = np.array(c_in) + c_input = tf.compat.v1.convert_to_tensor(c_in, tf.float64) + sess = tf.InteractiveSession() + #'finding the output of the input layer' + with tf.compat.v1.variable_scope("weight_in", reuse=tf.compat.v1.AUTO_REUSE): + weight_i = tf.compat.v1.get_variable("weight_input", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.weight_initer) + init_i = tf.compat.v1.global_variables_initializer() + sess.run(init_i) + with tf.compat.v1.variable_scope("weight_hid", reuse=tf.compat.v1.AUTO_REUSE): + weight_h = tf.compat.v1.get_variable("weight_hidden", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.weight_initer1) + init_h = tf.compat.v1.global_variables_initializer() + sess.run(init_h) + with tf.compat.v1.variable_scope("weight_out", reuse=tf.compat.v1.AUTO_REUSE): + weight_o = tf.compat.v1.get_variable("weight_input", dtype=tf.float64, shape=[4, 2], initializer=self.weight_initer2) + init_o = tf.compat.v1.global_variables_initializer() + sess.run(init_o) + with tf.compat.v1.variable_scope("bias_in", reuse=tf.compat.v1.AUTO_REUSE): + bias_i = tf.compat.v1.get_variable("bias_input", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.bias_initer) + init_i_b = tf.compat.v1.global_variables_initializer() + sess.run(init_i_b) + with tf.compat.v1.variable_scope("bias_hid", reuse=tf.compat.v1.AUTO_REUSE): + bias_h = tf.compat.v1.get_variable("bias_hidden", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.bias_initer1) + init_h_b = tf.compat.v1.global_variables_initializer() + sess.run(init_h_b) + with tf.compat.v1.variable_scope("bias_out", reuse=tf.compat.v1.AUTO_REUSE): + bias_o = tf.compat.v1.get_variable("bias_out", dtype=tf.float64, shape=[1, 4], initializer=self.bias_initer2) + init_o_b = tf.compat.v1.global_variables_initializer() + sess.run(init_o_b) + uninitialized_variables = [] + #print("printing the names of all variables") + #print(tf.all_variables()) + for var in tf.all_variables(): + try: + sess.run(var) + except tf.errors.FailedPreconditionError: + uninitialized_variables.append(var) + + init = tf.variables_initializer(uninitialized_variables) + sess.run(init) + #print("priniting uninitialized variables") + #print(sess.run(tf.report_uninitialized_variables(uninitialized_variables))) + knowledge_input = tf.compat.v1.add(tf.compat.v1.multiply(c_input, weight_i), bias_i) + #sess.run(knowledge_input) + knowledge_hidden = tf.compat.v1.nn.leaky_relu(knowledge_input, alpha=0.01) + #'calculating the output of hidden layer' + knowledge_hidden_output = 3.14*(tf.compat.v1.add(tf.compat.v1.multiply(knowledge_hidden, weight_h), bias_h))#input function of hidden layer + knowledge_hidden_out = tf.compat.v1.nn.leaky_relu(knowledge_hidden_output, alpha=0.01, name='leaky_relu') + + #sess.run(knowledge_hidden_out) + #'calculating the input of output layer' + knowledge_hidden_out = tf.compat.v1.reshape(knowledge_hidden_out, [4, 2])#for quadrant method + out_mult = tf.compat.v1.multiply(knowledge_hidden_out, weight_o) + out_add = tf.compat.v1.add(out_mult[:, 0], out_mult[:, 1]) + in_out = tf.compat.v1.add(out_add, bias_o) + #deb = sess.run(in_out) + #print("printing the shape of tensor in last layer") + #print(tf.shape(in_out)) + #print(deb) + in_out = tf.compat.v1.reshape(in_out, [1, 4]) + #i_o = sess.run(in_out) + #r_i_o = np.reshape(i_o, (8, 1)) + #outt = np.add(r_i_o[0:4, 0], r_i_o[4:8, 0]) + #outt = np.reshape(outt, (4, 1)) + #out_multt = tf.placeholder(tf.float64, shape=(4, 1)) + #in_outt = tf.add(out_multt, bias_o) + output = sess.run(in_out) + variables_list_kt = tf.trainable_variables() + variables_kt = sess.run(variables_list_kt) + variables_list_kt, variables_kt = self.get_var_list() + for var, val in zip(variables_kt, variables_list_kt): + #print("var: {}, value: {}".format(var.name, val)) + k_dict[var.name] = val + #output = sess.run(in_out) + #'finding the softmax output of the neurons' + #just testing + #softmax_output = tf.nn.softmax(in_out) + #output = sess.run(softmax_output) + sess.close() + return output, in_out, k_dict + def learn(self, preferred_out, soft_out): + self.kt_learning(0.1, soft_out, preferred_out) + +def one_hot_encoding(model_type): + a_1 = np.zeros((3)) + if (model_type == 1): + hot_encoded_matrix = np.insert(a_1, 0, 1, axis=None)#insert 1 in the first coloumn in x axis + elif(model_type == 2): + hot_encoded_matrix = np.insert(a_1, 1, 1, axis=None) + elif(model_type == 3): + hot_encoded_matrix = np.insert(a_1, 2, 1, axis=None) + elif(model_type == 4): + hot_encoded_matrix = np.insert(a_1, 3, 1, axis=None) + else: + raise ValueError(f"Value {model_type} is not a valid model number") + return hot_encoded_matrix \ No newline at end of file diff --git a/spider_control/kt.py b/spider_control/kt.py new file mode 100644 index 0000000000000000000000000000000000000000..ad7ba6ed278cd26d1425b0f03e20de41cc02b012 --- /dev/null +++ b/spider_control/kt.py @@ -0,0 +1,117 @@ +#!/usr/bin/python3 +import tensorflow as tf +import numpy as np +from matplotlib import pyplot +#import pyplot as plt +import math +import time + +class MultiClassLogistic: + + def __init__(self, neurons, layers): + self.neurons = neurons + self.layers = layers + self.mygraph = tf.Graph() + self.weight_initer = tf.truncated_normal_initializer(mean=0.0, stddev=0.01) + self.neuron_input = tf.compat.v1.placeholder(tf.float32, shape=(self.neurons, 1)) + self.weight_in = tf.get_variable(name="Weight_input", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.weight_initer) + self.neuron_hid = tf.compat.v1.placeholder(tf.float32, shape=(int(self.neurons/2), 1)) + self.weight_initer1 = tf.truncated_normal_initializer(mean=1.0, stddev=0.01) + self.weight_hid = tf.get_variable(name="Weight_hidden", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.weight_initer1) + self.neuron_out = tf.compat.v1.placeholder(tf.float32, shape=(4, 1)) + self.weight_initer2 = tf.truncated_normal_initializer(mean=2.0, stddev=0.01) + self.weight_out = tf.get_variable(name="Weight_output", dtype=tf.float64, shape=[4, 2], initializer=self.weight_initer2) + self.bias_initer =tf.truncated_normal_initializer(mean=0.1, stddev=0.01) + self.bias_in =tf.get_variable(name="Bias_input", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.bias_initer) + self.bias_initer1 =tf.truncated_normal_initializer(mean=0.2, stddev=0.01) + self.bias_hid = tf.get_variable(name="Bias_hidden", dtype=tf.float64, shape=[self.neurons, 1], initializer=self.bias_initer1) + self.bias_initer2 =tf.truncated_normal_initializer(mean=0.3, stddev=0.01) + self.bias_out = tf.get_variable(name="Bias_output", dtype=tf.float64, shape=[4, 1], initializer=self.bias_initer2) + + #defining input function that can accept the output from previous layer and can calculate the input for present layer + + #def input_function(self, a = [], b = [], c = []): + # 'where b=output value of neurons from previous layer, a = weights of neurons from the present layer, c = bias' + # multiplication = tf.multiply(a, b) + # add = tf.add(multiplication, c) + # sess = tf.Session() + # n_input = sess.run(add) + # return n_input + #function that returns the softmax of the output layer or any given array of neurons + def out_softmax(self, neuron_out = []): + output = tf.nn.softmax(neuron_out) + with tf.Session() as sess: + out = sess.run(output) + return out + + def kt_learning(self, learning_rate, n_out = [], n_preferred = []): + 'where n_out is the actual output and n_preffered is the prefered output of the network' + loss = tf.reduce_mean(tf.nn.softmax_cross_entropy_with_logits(labels=n_out, logits=n_preferred)) + optimizer = tf.train.GradientDescentOptimizer(learning_rate).minimize(loss) + with tf.Session() as sess: + sess.run(optimizer) + return + + #def get_neuron(self, a, b): + # #'while a being the name of the neuron and b being the value of that neuron' + # with tf.Session() as sess_n: + # sess_n.run(a, feed_dict={a: b}) + #'a function to findout the input of the neurn giving its weights and biases, can only be used in neurons in hidden and output layer' + #def input_method(self, a=[], b=[], c=[]): + # multiplication = tf.multiply(a, b) + # d = tf.reduce_sum(multiplication, 0) + # add = tf.add(d, c) + # with tf.Session() as sess: + # out = sess.run(add) + # return out + def normalization(self, inputs): + a_min = min(inputs) + a_max = max(inputs) + for i in range(len(inputs)): + inputs[i] = (inputs[i]-a_min)/(a_max-a_min) + + def run(self, carollis_input): + self.normalization(carollis_input) + #'finding the output of the input layer' + #with tf.Session() as sess1_2: + + knowledge_input = tf.add(tf.multiply(carollis_input, self.weight_in), self.bias_in) + + #'calculating the input for the hidden layer' + knowledge_hidden = tf.add(tf.multiply(knowledge_input, self.weight_in), self.bias_hid) + #'calculating the output of hidden layer' + knowledge_hidden_output = 3.14*(tf.add(tf.multiply(knowledge_hidden, self.weight_hid), self.bias_hid))#input function of hidden layer + knowledge_hidden_out = tf.nn.leaky_relu(knowledge_hidden_output, alpha=0.01, name='leaky_relu') + + with tf.Session() as sess1_2: + knowledge_hidden_out1 = sess1_2.run(knowledge_hidden_out) + #'calculating the input of output layer' + tf.reshape(knowledge_hidden_out1, [4, 2])#for quadrant method + in_out = tf.add(tf.multiply(knowledge_hidden_out1, self.weight_out), self.bias_out) + with tf.Session() as s: + s.run(in_out) + #'finding the softmax output of the neurons' + softmax_output = np.array(4) + softmax_output = self.out_softmax(in_out) # this gives the softmax output and stores it in the newly created array + return softmax_output + def learn(self, preferred_out, soft_out): + self.kt_learning(0.1, soft_out, preferred_out) + +def one_hot_encoding(model_type): + a_1 = np.zeros((3)) + if (model_type == 1): + hot_encoded_matrix = np.insert(a_1, 0, 1, axis=None)#insert 1 in the first coloumn in x axis + elif(model_type == 2): + hot_encoded_matrix = np.insert(a_1, 1, 1, axis=None) + elif(model_type == 3): + hot_encoded_matrix = np.insert(a_1, 2, 1, axis=None) + elif(model_type == 4): + hot_encoded_matrix = np.insert(a_1, 3, 1, axis=None) + else: + raise ValueError(f"Value {model_type} is not a valid model number") + return hot_encoded_matrix + +if __name__=='__main__': + knowledge = MultiClassLogistic(8, 3) + io = np.array([6.45, 4.54, 7, 8.98, 8.88, 12.34, 25.76, 1.67]) + knowledge_out = knowledge.run(io) \ No newline at end of file diff --git a/spider_control/launch/spider_control.launch b/spider_control/launch/spider_control.launch index fe0c53609df7ed2c6adad7fa7e71bf74b4de1060..92dcf6c6fe2fe6a22d906cae8d3e0b6d875336ec 100644 --- a/spider_control/launch/spider_control.launch +++ b/spider_control/launch/spider_control.launch @@ -5,8 +5,8 @@ + joint_8_3_position_controller + joint_state_controller"/> + + + + [/spider/joint_states] + + respawn="false" output="screen" ns="/spider" > + + diff --git a/spider_control/leg_dynamics.py b/spider_control/leg_dynamics.py new file mode 100755 index 0000000000000000000000000000000000000000..c265c045a78d4cf4f85df45a2e3523ebf308589d --- /dev/null +++ b/spider_control/leg_dynamics.py @@ -0,0 +1,154 @@ +#!/usr/bin/python3 +import tensorflow as tf +import numpy as np +from matplotlib import pylab +import pylab as plt +import math +import time + +class Leg_attribute: + m_l = 1 # mass of the link in every leg + m_b = 4 # mass of the body + x_b = 0 + y_b = 0 + l_1 = 4 # length of the links 1 and 2 of every leg + l_3 = 6 # length of the link 3 from every leg i.e. distal joint + r_1 = 2 # centre of gravity of links 1 and 2 from every leg + r_3 = 3 # centre of gravity of links 3 from every leg i.e. distal link from distal joint + radius = 0.5 #radius of the links + global acc #acceleration at which the robot is supposed to move + j_angles = [] #np.ones((1, 3)) # in radians + j_velocities = [] #np.ones((1,3)) + j_efforts = [] #np.ones((1, 3)) + #touch = False #variable to detect whether tactile sensor touch the ground or not + def __init__(self, j_angles, velocity, effort, tactile): + self.j_angles = j_angles # vector containing the joint angles + self.velocity = velocity # vector containing joint velocities + self.j_efforts = effort # vector containing efforts of each joint in the leg + self.tactile = tactile + self.m = 0.3 + self.g = 9.8 + self.r = 0.1 + self.l = 0.4 + self.L = 0.6 + self.M = 2.8 + def update_angles(self, angles): + self.j_angles = angles + def update_velocity(self, veloc): + self.velocity = veloc + def update_tactile(self, tac): + self.tactile = tac + def update_effort(self, ef): + self.j_effort = ef + def give_angles(self): + return self.j_angles + + + + def x_left_com(self): + return (1/(2*(self.M/2+6*self.g)))*(self.M/2*self.l+2*self.g*self.r*(3*(math.cos(self.j_angles[2])+math.cos(self.j_angles[8])+math.cos(self.j_angles[14])+math.cos(self.j_angles[20]))+2*(math.cos(self.j_angles[1])+math.cos(self.j_angles[7])+math.cos(self.j_angles[13])+math.cos(self.j_angles[19]))+math.cos(self.j_angles[0])+math.cos(self.j_angles[6])+math.cos(self.j_angles[12])+math.cos(self.j_angles[18]))) + + #a,b,c,d,e,f,j,k,l,m,n,o,p are respectively m_b,m_l,L,x_body_com/y_body_com,theta_1_1,theta_1_2,...theta_8_3 + + def y_left_com(self): + return (1/(2*(self.M/2+6*self.g)))*(self.M/2*self.l+2*self.g*self.r*(3*(math.sin(self.j_angles[2])+3*math.sin(self.j_angles[8])+math.sin(self.j_angles[14])+math.sin(self.j_angles[20]))+2*(math.sin(self.j_angles[1])+math.sin(self.j_angles[7])+math.sin(self.j_angles[13])+math.sin(self.j_angles[19]))+math.sin(self.j_angles[0])+math.sin(self.j_angles[6])+math.sin(self.j_angles[12])+math.sin(self.j_angles[18]))) + + def x_right_com(self): + return (1/(2*(self.M/2+6*self.g)))*(3*self.M/2*self.l+2*self.g*self.r*(3*math.cos(self.j_angles[5])+3*math.cos(self.j_angles[11])+3*math.cos(self.j_angles[17])+3*math.cos(self.j_angles[23])+2*math.cos(self.j_angles[4])+2*math.cos(self.j_angles[10])+2*math.cos(self.j_angles[16])+2*math.cos(self.j_angles[22])+math.cos(self.j_angles[3])+math.cos(self.j_angles[9])+math.cos(self.j_angles[15])+math.cos(self.j_angles[21]))) + + def y_right_com(self): + return (1/(2*(self.M/2+6*self.g)))*(3*self.M/2*self.l+2*self.g*self.r*(3*math.sin(self.j_angles[5])+3*math.sin(self.j_angles[11])+3*math.sin(self.j_angles[17])+3*math.sin(self.j_angles[23])+2*math.sin(self.j_angles[4])+2*math.sin(self.j_angles[10])+2*math.sin(self.j_angles[16])+2*math.sin(self.j_angles[22])+math.sin(self.j_angles[3])+math.sin(self.j_angles[9])+math.sin(self.j_angles[15])+math.sin(self.j_angles[21]))) + + def x_system_com(self): + return (1/(self.M/2+6*self.g*self.r))*(2*self.M/2*self.l+self.g*self.r*(3*(math.cos(self.j_angles[2])+math.cos(self.j_angles[5])+math.cos(self.j_angles[8])+math.cos(self.j_angles[11])+math.cos(self.j_angles[14])+math.cos(self.j_angles[17])+math.cos(self.j_angles[20])+math.cos(self.j_angles[23]))+2*(math.cos(self.j_angles[1])+math.cos(self.j_angles[4])+math.cos(self.j_angles[7])+math.cos(self.j_angles[10])+math.cos(self.j_angles[13])+math.cos(self.j_angles[16])+math.cos(self.j_angles[19])+math.cos(self.j_angles[22]))+math.cos(self.j_angles[0])+math.cos(self.j_angles[3])+math.cos(self.j_angles[6])+math.cos(self.j_angles[9])+math.cos(self.j_angles[12])+math.cos(self.j_angles[15])+math.cos(self.j_angles[18])+math.cos(self.j_angles[21]))) + + def y_system_com(self): + return (1/(self.M/2+6*self.g*self.r))*(2*self.M/2*self.l+self.g*self.r*(3*(math.sin(self.j_angles[2])+math.sin(self.j_angles[5])+math.sin(self.j_angles[8])+math.sin(self.j_angles[11])+math.sin(self.j_angles[14])+math.sin(self.j_angles[17])+math.sin(self.j_angles[20])+math.sin(self.j_angles[23]))+2*(math.sin(self.j_angles[1])+math.sin(self.j_angles[4])+math.sin(self.j_angles[7])+math.sin(self.j_angles[10])+math.sin(self.j_angles[13])+math.sin(self.j_angles[16])+math.sin(self.j_angles[19])+math.sin(self.j_angles[22]))+math.sin(self.j_angles[0])+math.sin(self.j_angles[3])+math.sin(self.j_angles[6])+math.sin(self.j_angles[9])+math.sin(self.j_angles[12])+math.sin(self.j_angles[15])+math.sin(self.j_angles[18])+math.sin(self.j_angles[21]))) + + def mid_point_x(self, x_left, x_right): + 'in order to calculate whether the syste com is normal to the line between left and right com' + x_mid = (x_right + x_left)/2 + return x_mid + + def mid_point_y(self, y_left, y_right): + 'in order to calculate whether the system com is normal to the line between left and right com' + y_mid = (y_right + y_left)/2 + return y_mid + + def slope(self, x_mid, y_mid, x_system, y_system): + 'slope to measure the balance of the robot that can be used to define reward or punishment' + m = (y_system - y_mid)/(x_system - x_mid) + m_radian = (m*3.14)/180 + return m_radian + + #calculates carolis term for each leg + def carolis_term(self, acc, m_l, r_1, l_1, j_angles=[], j_velocities=[]): + term_1 = acc*(m_l*9.8*j_velocities[0]*(r_1*math.sin(j_angles[0])+2*l_1*math.sin(j_angles[0])+r_1*math.sin(j_angles[0]+j_angles[1])+r_1*math.sin(j_angles[0]+j_angles[1]+j_angles[2]))+m_l*9.8*j_velocities[1]*(r_1*math.sin(j_angles[0]+j_angles[1])+l_1*math.sin(j_angles[1])+r_1*math.sin(j_angles[0]+j_angles[1]+j_angles[2]))+m_l*9.8*j_velocities[2]*(r_1*math.sin(j_angles[0]+j_angles[1]+j_angles[2]))) + term_2 = acc*(m_l*9.8*j_velocities[0]*(r_1*math.sin(j_angles[0]+j_angles[1])+r_1*math.sin(j_angles[0]+j_angles[1]+j_angles[2]))+m_l*9.8*j_velocities[1]*(r_1*math.sin(j_angles[0]+j_angles[1])+l_1*math.sin(j_angles[1])+r_1*math.sin(j_angles[0]+j_angles[1]+j_angles[2]))+m_l*9.8*j_velocities[2]*math.sin(j_angles[0]+j_angles[1]+j_angles[2])) + term_3 = acc*(m_l*9.8*j_velocities[0]*math.sin(j_angles[0]+j_angles[1]+j_angles[2])+m_l*9.8*j_velocities[1]*math.sin(j_angles[0]+j_angles[1]+j_angles[2])+m_l*9.8*j_velocities[2]*math.sin(j_angles[0]+j_angles[1]+j_angles[2])) + term = term_1 +term_2 + term_3 + return term + + def tactile_run(self): + score = 0 + total = 0 + if(sum(self.tactile) != 0): + for element in range(0, len(self.tactile)): + if(self.tactile[element]>0.5): + total +=1 + if(total>3): + score = total + else: + score = 0 + else: + score = 0 + return score + + def carollis_input(self): + term_1_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[0])+2*self.l_1*math.sin(self.j_angles[0])+self.r_1*math.sin(self.j_angles[0]+self.j_angles[1])+self.r_1*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[0]+self.j_angles[1])+self.l_1*math.sin(self.j_angles[1])+self.r_1*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2]))) + term_1_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[0]+self.j_angles[1])+self.r_1*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[0]+self.j_angles[1])+self.l_1*math.sin(self.j_angles[1])+self.r_1*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2])) + term_1_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[0]+self.j_angles[1]+self.j_angles[2])) + term_2_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[3])+2*self.l_1*math.sin(self.j_angles[3])+self.r_1*math.sin(self.j_angles[3]+self.j_angles[4])+self.r_1*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[3]+self.j_angles[4])+self.l_1*math.sin(self.j_angles[4])+self.r_1*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5]))) + term_2_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[3]+self.j_angles[4])+self.r_1*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[3]+self.j_angles[4])+self.l_1*math.sin(self.j_angles[4])+self.r_1*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5])) + term_2_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[3]+self.j_angles[4]+self.j_angles[5])) + term_3_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[6])+2*self.l_1*math.sin(self.j_angles[6])+self.r_1*math.sin(self.j_angles[6]+self.j_angles[7])+self.r_1*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[6]+self.j_angles[7])+self.l_1*math.sin(self.j_angles[7])+self.r_1*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8]))) + term_3_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[6]+self.j_angles[7])+self.r_1*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[6]+self.j_angles[7])+self.l_1*math.sin(self.j_angles[7])+self.r_1*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8])) + term_3_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[6]+self.j_angles[7]+self.j_angles[8])) + term_4_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[9])+2*self.l_1*math.sin(self.j_angles[9])+self.r_1*math.sin(self.j_angles[9]+self.j_angles[10])+self.r_1*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[9]+self.j_angles[10])+self.l_1*math.sin(self.j_angles[10])+self.r_1*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11]))) + term_4_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[9]+self.j_angles[10])+self.r_1*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[9]+self.j_angles[10])+self.l_1*math.sin(self.j_angles[10])+self.r_1*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11])) + term_4_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[9]+self.j_angles[10]+self.j_angles[11])) + term_5_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[12])+2*self.l_1*math.sin(self.j_angles[12])+self.r_1*math.sin(self.j_angles[12]+self.j_angles[13])+self.r_1*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[12]+self.j_angles[13])+self.l_1*math.sin(self.j_angles[13])+self.r_1*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14]))) + term_5_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[12]+self.j_angles[13])+self.r_1*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[12]+self.j_angles[13])+self.l_1*math.sin(self.j_angles[13])+self.r_1*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14])) + term_5_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[12]+self.j_angles[13]+self.j_angles[14])) + term_6_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[15])+2*self.l_1*math.sin(self.j_angles[15])+self.r_1*math.sin(self.j_angles[15]+self.j_angles[16])+self.r_1*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[15]+self.j_angles[16])+self.l_1*math.sin(self.j_angles[16])+self.r_1*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17]))) + term_6_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[15]+self.j_angles[16])+self.r_1*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[15]+self.j_angles[16])+self.l_1*math.sin(self.j_angles[16])+self.r_1*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17])) + term_6_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[15]+self.j_angles[16]+self.j_angles[17])) + term_7_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[18])+2*self.l_1*math.sin(self.j_angles[18])+self.r_1*math.sin(self.j_angles[18]+self.j_angles[19])+self.r_1*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[18]+self.j_angles[19])+self.l_1*math.sin(self.j_angles[19])+self.r_1*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20]))) + term_7_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[18]+self.j_angles[19])+self.r_1*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[18]+self.j_angles[19])+self.l_1*math.sin(self.j_angles[19])+self.r_1*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20])) + term_7_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[18]+self.j_angles[19]+self.j_angles[20])) + term_8_1 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[21])+2*self.l_1*math.sin(self.j_angles[21])+self.r_1*math.sin(self.j_angles[21]+self.j_angles[22])+self.r_1*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[21]+self.j_angles[22])+self.l_1*math.sin(self.j_angles[22])+self.r_1*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23]))) + term_8_2 = (self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[21]+self.j_angles[22])+self.r_1*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23]))+self.m_l*9.8*self.velocity*(self.r_1*math.sin(self.j_angles[21]+self.j_angles[22])+self.l_1*math.sin(self.j_angles[22])+self.r_1*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23]))+self.m_l*9.8*self.velocity*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23])) + term_8_3 = (self.m_l*9.8*self.velocity*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23])+self.m_l*9.8*self.velocity*math.sin(self.j_angles[21]+self.j_angles[22]+self.j_angles[23])) + term1 = term_1_1 +term_1_2 + term_1_3 + term2 = term_2_1+term_2_2+term_2_3 + term3 = term_3_1+term_3_2+term_3_3 + term4 = term_4_1+term_4_2+term_4_3 + term5 = term_5_1+term_5_2+term_5_3 + term6 = term_6_1+term_6_2+term_6_3 + term7 = term_7_1+term_7_2+term_7_3 + term8 = term_8_1+term_8_2+term_8_3 + term = np.array([[term1], [term2], [term3], [term4], [term5], [term6], [term7], [term8]]) + return term + def leg_run(self): + x_l_com = self.x_left_com() + y_l_com = self.y_left_com() + x_r_com = self.x_right_com() + y_r_com = self.y_right_com() + x_s_com = self.x_system_com() + y_s_com = self.y_system_com() + x_m_com = self.mid_point_x(x_l_com, x_r_com) + y_m_com = self.mid_point_y(y_l_com, y_r_com) + reward_stability = self.slope(x_m_com, y_m_com, x_s_com, y_s_com) + reward_tactile = self.tactile_run() + reward = reward_stability+reward_tactile + return reward \ No newline at end of file diff --git a/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake b/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake new file mode 100644 index 0000000000000000000000000000000000000000..81692d85d3f10d49b4a072fef74d30399cc031b2 --- /dev/null +++ b/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake @@ -0,0 +1,2 @@ +set(geometry_msgs_MESSAGE_FILES "msg/Accel.msg;msg/AccelStamped.msg;msg/AccelWithCovariance.msg;msg/AccelWithCovarianceStamped.msg;msg/Inertia.msg;msg/InertiaStamped.msg;msg/Point.msg;msg/Point32.msg;msg/PointStamped.msg;msg/Polygon.msg;msg/PolygonStamped.msg;msg/Pose2D.msg;msg/Pose.msg;msg/PoseArray.msg;msg/PoseStamped.msg;msg/PoseWithCovariance.msg;msg/PoseWithCovarianceStamped.msg;msg/Quaternion.msg;msg/QuaternionStamped.msg;msg/Transform.msg;msg/TransformStamped.msg;msg/Twist.msg;msg/TwistStamped.msg;msg/TwistWithCovariance.msg;msg/TwistWithCovarianceStamped.msg;msg/Vector3.msg;msg/Vector3Stamped.msg;msg/Wrench.msg;msg/WrenchStamped.msg") +set(geometry_msgs_SERVICE_FILES "") diff --git a/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-paths.cmake b/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-paths.cmake new file mode 100644 index 0000000000000000000000000000000000000000..a2e168324044612198d168f9f317d15c3dc8bcff --- /dev/null +++ b/spider_control/msg/geometry_msgs/cmake/geometry_msgs-msg-paths.cmake @@ -0,0 +1,4 @@ +# generated from genmsg/cmake/pkg-msg-paths.cmake.installspace.in + +_prepend_path("${geometry_msgs_DIR}/.." "msg" geometry_msgs_MSG_INCLUDE_DIRS UNIQUE) +set(geometry_msgs_MSG_DEPENDENCIES std_msgs) diff --git a/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig-version.cmake b/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig-version.cmake new file mode 100644 index 0000000000000000000000000000000000000000..20c93291af12ed54520d694ebacc76df45fa6e0f --- /dev/null +++ b/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig-version.cmake @@ -0,0 +1,14 @@ +# generated from catkin/cmake/template/pkgConfig-version.cmake.in +set(PACKAGE_VERSION "1.12.7") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig.cmake b/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig.cmake new file mode 100644 index 0000000000000000000000000000000000000000..dab7b68470c812574f19ea4b74175adb04315c9f --- /dev/null +++ b/spider_control/msg/geometry_msgs/cmake/geometry_msgsConfig.cmake @@ -0,0 +1,200 @@ +# generated from catkin/cmake/template/pkgConfig.cmake.in + +# append elements to a list and remove existing duplicates from the list +# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig +# self contained +macro(_list_append_deduplicate listname) + if(NOT "${ARGN}" STREQUAL "") + if(${listname}) + list(REMOVE_ITEM ${listname} ${ARGN}) + endif() + list(APPEND ${listname} ${ARGN}) + endif() +endmacro() + +# append elements to a list if they are not already in the list +# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig +# self contained +macro(_list_append_unique listname) + foreach(_item ${ARGN}) + list(FIND ${listname} ${_item} _index) + if(_index EQUAL -1) + list(APPEND ${listname} ${_item}) + endif() + endforeach() +endmacro() + +# pack a list of libraries with optional build configuration keywords +# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig +# self contained +macro(_pack_libraries_with_build_configuration VAR) + set(${VAR} "") + set(_argn ${ARGN}) + list(LENGTH _argn _count) + set(_index 0) + while(${_index} LESS ${_count}) + list(GET _argn ${_index} lib) + if("${lib}" MATCHES "^(debug|optimized|general)$") + math(EXPR _index "${_index} + 1") + if(${_index} EQUAL ${_count}) + message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library") + endif() + list(GET _argn ${_index} library) + list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}") + else() + list(APPEND ${VAR} "${lib}") + endif() + math(EXPR _index "${_index} + 1") + endwhile() +endmacro() + +# unpack a list of libraries with optional build configuration keyword prefixes +# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig +# self contained +macro(_unpack_libraries_with_build_configuration VAR) + set(${VAR} "") + foreach(lib ${ARGN}) + string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}") + list(APPEND ${VAR} "${lib}") + endforeach() +endmacro() + + +if(geometry_msgs_CONFIG_INCLUDED) + return() +endif() +set(geometry_msgs_CONFIG_INCLUDED TRUE) + +# set variables for source/devel/install prefixes +if("FALSE" STREQUAL "TRUE") + set(geometry_msgs_SOURCE_PREFIX /tmp/binarydeb/ros-melodic-geometry-msgs-1.12.7) + set(geometry_msgs_DEVEL_PREFIX /tmp/binarydeb/ros-melodic-geometry-msgs-1.12.7/obj-x86_64-linux-gnu/devel) + set(geometry_msgs_INSTALL_PREFIX "") + set(geometry_msgs_PREFIX ${geometry_msgs_DEVEL_PREFIX}) +else() + set(geometry_msgs_SOURCE_PREFIX "") + set(geometry_msgs_DEVEL_PREFIX "") + set(geometry_msgs_INSTALL_PREFIX /opt/ros/melodic) + set(geometry_msgs_PREFIX ${geometry_msgs_INSTALL_PREFIX}) +endif() + +# warn when using a deprecated package +if(NOT "" STREQUAL "") + set(_msg "WARNING: package 'geometry_msgs' is deprecated") + # append custom deprecation text if available + if(NOT "" STREQUAL "TRUE") + set(_msg "${_msg} ()") + endif() + message("${_msg}") +endif() + +# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project +set(geometry_msgs_FOUND_CATKIN_PROJECT TRUE) + +if(NOT "include " STREQUAL " ") + set(geometry_msgs_INCLUDE_DIRS "") + set(_include_dirs "include") + if(NOT " " STREQUAL " ") + set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.") + elseif(NOT "http://wiki.ros.org/geometry_msgs " STREQUAL " ") + set(_report "Check the website 'http://wiki.ros.org/geometry_msgs' for information and consider reporting the problem.") + else() + set(_report "Report the problem to the maintainer 'Tully Foote ' and request to fix the problem.") + endif() + foreach(idir ${_include_dirs}) + if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir}) + set(include ${idir}) + elseif("${idir} " STREQUAL "include ") + get_filename_component(include "${geometry_msgs_DIR}/../../../include" ABSOLUTE) + if(NOT IS_DIRECTORY ${include}) + message(FATAL_ERROR "Project 'geometry_msgs' specifies '${idir}' as an include dir, which is not found. It does not exist in '${include}'. ${_report}") + endif() + else() + message(FATAL_ERROR "Project 'geometry_msgs' specifies '${idir}' as an include dir, which is not found. It does neither exist as an absolute directory nor in '/opt/ros/melodic/${idir}'. ${_report}") + endif() + _list_append_unique(geometry_msgs_INCLUDE_DIRS ${include}) + endforeach() +endif() + +set(libraries "") +foreach(library ${libraries}) + # keep build configuration keywords, target names and absolute libraries as-is + if("${library}" MATCHES "^(debug|optimized|general)$") + list(APPEND geometry_msgs_LIBRARIES ${library}) + elseif(${library} MATCHES "^-l") + list(APPEND geometry_msgs_LIBRARIES ${library}) + elseif(TARGET ${library}) + list(APPEND geometry_msgs_LIBRARIES ${library}) + elseif(IS_ABSOLUTE ${library}) + list(APPEND geometry_msgs_LIBRARIES ${library}) + else() + set(lib_path "") + set(lib "${library}-NOTFOUND") + # since the path where the library is found is returned we have to iterate over the paths manually + foreach(path /opt/ros/melodic/lib;/opt/ros/melodic/lib) + find_library(lib ${library} + PATHS ${path} + NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH) + if(lib) + set(lib_path ${path}) + break() + endif() + endforeach() + if(lib) + _list_append_unique(geometry_msgs_LIBRARY_DIRS ${lib_path}) + list(APPEND geometry_msgs_LIBRARIES ${lib}) + else() + # as a fall back for non-catkin libraries try to search globally + find_library(lib ${library}) + if(NOT lib) + message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'. The library is neither a target nor built/installed properly. Did you compile project 'geometry_msgs'? Did you find_package() it before the subdirectory containing its code is included?") + endif() + list(APPEND geometry_msgs_LIBRARIES ${lib}) + endif() + endif() +endforeach() + +set(geometry_msgs_EXPORTED_TARGETS "geometry_msgs_generate_messages_cpp;geometry_msgs_generate_messages_eus;geometry_msgs_generate_messages_lisp;geometry_msgs_generate_messages_nodejs;geometry_msgs_generate_messages_py") +# create dummy targets for exported code generation targets to make life of users easier +foreach(t ${geometry_msgs_EXPORTED_TARGETS}) + if(NOT TARGET ${t}) + add_custom_target(${t}) + endif() +endforeach() + +set(depends "message_runtime;std_msgs") +foreach(depend ${depends}) + string(REPLACE " " ";" depend_list ${depend}) + # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls + list(GET depend_list 0 geometry_msgs_dep) + list(LENGTH depend_list count) + if(${count} EQUAL 1) + # simple dependencies must only be find_package()-ed once + if(NOT ${geometry_msgs_dep}_FOUND) + find_package(${geometry_msgs_dep} REQUIRED NO_MODULE) + endif() + else() + # dependencies with components must be find_package()-ed again + list(REMOVE_AT depend_list 0) + find_package(${geometry_msgs_dep} REQUIRED NO_MODULE ${depend_list}) + endif() + _list_append_unique(geometry_msgs_INCLUDE_DIRS ${${geometry_msgs_dep}_INCLUDE_DIRS}) + + # merge build configuration keywords with library names to correctly deduplicate + _pack_libraries_with_build_configuration(geometry_msgs_LIBRARIES ${geometry_msgs_LIBRARIES}) + _pack_libraries_with_build_configuration(_libraries ${${geometry_msgs_dep}_LIBRARIES}) + _list_append_deduplicate(geometry_msgs_LIBRARIES ${_libraries}) + # undo build configuration keyword merging after deduplication + _unpack_libraries_with_build_configuration(geometry_msgs_LIBRARIES ${geometry_msgs_LIBRARIES}) + + _list_append_unique(geometry_msgs_LIBRARY_DIRS ${${geometry_msgs_dep}_LIBRARY_DIRS}) + list(APPEND geometry_msgs_EXPORTED_TARGETS ${${geometry_msgs_dep}_EXPORTED_TARGETS}) +endforeach() + +set(pkg_cfg_extras "geometry_msgs-msg-extras.cmake") +foreach(extra ${pkg_cfg_extras}) + if(NOT IS_ABSOLUTE ${extra}) + set(extra ${geometry_msgs_DIR}/${extra}) + endif() + include(${extra}) +endforeach() diff --git a/spider_control/msg/geometry_msgs/msg/Accel.msg b/spider_control/msg/geometry_msgs/msg/Accel.msg new file mode 100644 index 0000000000000000000000000000000000000000..19fef1411b7704ca358a27ce11111204befa5237 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Accel.msg @@ -0,0 +1,3 @@ +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular diff --git a/spider_control/msg/geometry_msgs/msg/AccelStamped.msg b/spider_control/msg/geometry_msgs/msg/AccelStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..8fc5940381cdedafc0286ee58f807a1c950152b1 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/AccelStamped.msg @@ -0,0 +1,3 @@ +# An accel with reference coordinate frame and timestamp +Header header +Accel accel diff --git a/spider_control/msg/geometry_msgs/msg/AccelWithCovariance.msg b/spider_control/msg/geometry_msgs/msg/AccelWithCovariance.msg new file mode 100644 index 0000000000000000000000000000000000000000..fb9674d306149013e1b87f816a3e4c7b68759713 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/AccelWithCovariance.msg @@ -0,0 +1,9 @@ +# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/spider_control/msg/geometry_msgs/msg/AccelWithCovarianceStamped.msg b/spider_control/msg/geometry_msgs/msg/AccelWithCovarianceStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..0fb21427aeda7f89109671488c29d63cbd7945ef --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/AccelWithCovarianceStamped.msg @@ -0,0 +1,3 @@ +# This represents an estimated accel with reference coordinate frame and timestamp. +Header header +AccelWithCovariance accel diff --git a/spider_control/msg/geometry_msgs/msg/Inertia.msg b/spider_control/msg/geometry_msgs/msg/Inertia.msg new file mode 100644 index 0000000000000000000000000000000000000000..8b214dfbdc678d1a4355d878199dd69012537c4d --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Inertia.msg @@ -0,0 +1,16 @@ +# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz diff --git a/spider_control/msg/geometry_msgs/msg/InertiaStamped.msg b/spider_control/msg/geometry_msgs/msg/InertiaStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..89d7f0b436f1b3575ec4b7076aa684793dc7f7ef --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/InertiaStamped.msg @@ -0,0 +1,2 @@ +Header header +Inertia inertia diff --git a/spider_control/msg/geometry_msgs/msg/Point.msg b/spider_control/msg/geometry_msgs/msg/Point.msg new file mode 100644 index 0000000000000000000000000000000000000000..f1d3a71a853c668f066de795ba5e0f4458f3f1c0 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Point.msg @@ -0,0 +1,4 @@ +# This contains the position of a point in free space +float64 x +float64 y +float64 z diff --git a/spider_control/msg/geometry_msgs/msg/Point32.msg b/spider_control/msg/geometry_msgs/msg/Point32.msg new file mode 100644 index 0000000000000000000000000000000000000000..52af0a29a13b606b40945c2fd96a6473d0b2067e --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Point32.msg @@ -0,0 +1,11 @@ +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z \ No newline at end of file diff --git a/spider_control/msg/geometry_msgs/msg/PointStamped.msg b/spider_control/msg/geometry_msgs/msg/PointStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..82c3437946ccaf5c65817a0485cde96992b622dc --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PointStamped.msg @@ -0,0 +1,3 @@ +# This represents a Point with reference coordinate frame and timestamp +Header header +Point point diff --git a/spider_control/msg/geometry_msgs/msg/Polygon.msg b/spider_control/msg/geometry_msgs/msg/Polygon.msg new file mode 100644 index 0000000000000000000000000000000000000000..c081fc4374ef1f3b560b441da7451829a98f5f76 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Polygon.msg @@ -0,0 +1,2 @@ +#A specification of a polygon where the first and last points are assumed to be connected +Point32[] points diff --git a/spider_control/msg/geometry_msgs/msg/PolygonStamped.msg b/spider_control/msg/geometry_msgs/msg/PolygonStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..c9ee413840b3c8bd47d9c41b13a6d68176b29f56 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PolygonStamped.msg @@ -0,0 +1,3 @@ +# This represents a Polygon with reference coordinate frame and timestamp +Header header +Polygon polygon diff --git a/spider_control/msg/geometry_msgs/msg/Pose.msg b/spider_control/msg/geometry_msgs/msg/Pose.msg new file mode 100644 index 0000000000000000000000000000000000000000..763708f7a98d12e0e27894bea3bdd0b085602f2f --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Pose.msg @@ -0,0 +1,3 @@ +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation diff --git a/spider_control/msg/geometry_msgs/msg/Pose2D.msg b/spider_control/msg/geometry_msgs/msg/Pose2D.msg new file mode 100644 index 0000000000000000000000000000000000000000..c83cc117bce4710305f098e7901d124cfb2cc1f2 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Pose2D.msg @@ -0,0 +1,13 @@ +# Deprecated +# Please use the full 3D pose. + +# In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing. + +# If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you. + + +# This expresses a position and orientation on a 2D manifold. + +float64 x +float64 y +float64 theta diff --git a/spider_control/msg/geometry_msgs/msg/PoseArray.msg b/spider_control/msg/geometry_msgs/msg/PoseArray.msg new file mode 100644 index 0000000000000000000000000000000000000000..4fe0cec7c78baf2a9ee60cb751d7f7d617a8fe3a --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PoseArray.msg @@ -0,0 +1,5 @@ +# An array of poses with a header for global reference. + +Header header + +Pose[] poses diff --git a/spider_control/msg/geometry_msgs/msg/PoseStamped.msg b/spider_control/msg/geometry_msgs/msg/PoseStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..7e3cdc57b7ba5856bce0cb954d20b7a74354bdc2 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PoseStamped.msg @@ -0,0 +1,3 @@ +# A Pose with reference coordinate frame and timestamp +Header header +Pose pose diff --git a/spider_control/msg/geometry_msgs/msg/PoseWithCovariance.msg b/spider_control/msg/geometry_msgs/msg/PoseWithCovariance.msg new file mode 100644 index 0000000000000000000000000000000000000000..86bc45adbb5d7d64e90556ac1f24ca8f725313cd --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PoseWithCovariance.msg @@ -0,0 +1,9 @@ +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/spider_control/msg/geometry_msgs/msg/PoseWithCovarianceStamped.msg b/spider_control/msg/geometry_msgs/msg/PoseWithCovarianceStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..cdc306b906075b54479aa7a6a0db66f7edbc2f45 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/PoseWithCovarianceStamped.msg @@ -0,0 +1,4 @@ +# This expresses an estimated pose with a reference coordinate frame and timestamp + +Header header +PoseWithCovariance pose diff --git a/spider_control/msg/geometry_msgs/msg/Quaternion.msg b/spider_control/msg/geometry_msgs/msg/Quaternion.msg new file mode 100644 index 0000000000000000000000000000000000000000..9f4fde2bf4c13dc86a95688e4b5254aaec186e2a --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Quaternion.msg @@ -0,0 +1,6 @@ +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w diff --git a/spider_control/msg/geometry_msgs/msg/QuaternionStamped.msg b/spider_control/msg/geometry_msgs/msg/QuaternionStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..62c2fdfe992c1a5eef9bf2c3a07aae7f7ad30b8a --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/QuaternionStamped.msg @@ -0,0 +1,4 @@ +# This represents an orientation with reference coordinate frame and timestamp. + +Header header +Quaternion quaternion diff --git a/spider_control/msg/geometry_msgs/msg/Transform.msg b/spider_control/msg/geometry_msgs/msg/Transform.msg new file mode 100644 index 0000000000000000000000000000000000000000..f605c85ea8ec4c4871bdb7d77db6e7011c63e86d --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Transform.msg @@ -0,0 +1,4 @@ +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation diff --git a/spider_control/msg/geometry_msgs/msg/TransformStamped.msg b/spider_control/msg/geometry_msgs/msg/TransformStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..223465cb25b8828888b90bf4c3734cc83b8769da --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/TransformStamped.msg @@ -0,0 +1,10 @@ +# This expresses a transform from coordinate frame header.frame_id +# to the coordinate frame child_frame_id +# +# This message is mostly used by the +# tf package. +# See its documentation for more information. + +Header header +string child_frame_id # the frame id of the child frame +Transform transform diff --git a/spider_control/msg/geometry_msgs/msg/Twist.msg b/spider_control/msg/geometry_msgs/msg/Twist.msg new file mode 100644 index 0000000000000000000000000000000000000000..7012c2dd87ea6702f8e37a9cfbb7aab10caa8f7d --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Twist.msg @@ -0,0 +1,3 @@ +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular diff --git a/spider_control/msg/geometry_msgs/msg/TwistStamped.msg b/spider_control/msg/geometry_msgs/msg/TwistStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..53b8253b4251a4c6637ddd85d9937d796558949c --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/TwistStamped.msg @@ -0,0 +1,3 @@ +# A twist with reference coordinate frame and timestamp +Header header +Twist twist diff --git a/spider_control/msg/geometry_msgs/msg/TwistWithCovariance.msg b/spider_control/msg/geometry_msgs/msg/TwistWithCovariance.msg new file mode 100644 index 0000000000000000000000000000000000000000..111a19c5f7da42f846ed9eaff26ffc6a515c9e5f --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/TwistWithCovariance.msg @@ -0,0 +1,9 @@ +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/spider_control/msg/geometry_msgs/msg/TwistWithCovarianceStamped.msg b/spider_control/msg/geometry_msgs/msg/TwistWithCovarianceStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..aba6ebe735871ba35218fcebe021fbef6e11d5d9 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/TwistWithCovarianceStamped.msg @@ -0,0 +1,3 @@ +# This represents an estimated twist with reference coordinate frame and timestamp. +Header header +TwistWithCovariance twist diff --git a/spider_control/msg/geometry_msgs/msg/Vector3.msg b/spider_control/msg/geometry_msgs/msg/Vector3.msg new file mode 100644 index 0000000000000000000000000000000000000000..2877783d0a235620515987ce0604085041132312 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Vector3.msg @@ -0,0 +1,10 @@ +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z \ No newline at end of file diff --git a/spider_control/msg/geometry_msgs/msg/Vector3Stamped.msg b/spider_control/msg/geometry_msgs/msg/Vector3Stamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..e68eb062bebd5bba3cbaf9f33beae5a207f72a51 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Vector3Stamped.msg @@ -0,0 +1,3 @@ +# This represents a Vector3 with reference coordinate frame and timestamp +Header header +Vector3 vector diff --git a/spider_control/msg/geometry_msgs/msg/Wrench.msg b/spider_control/msg/geometry_msgs/msg/Wrench.msg new file mode 100644 index 0000000000000000000000000000000000000000..41201d4b844607ee2d3751f3f474774a2ae1e387 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/Wrench.msg @@ -0,0 +1,4 @@ +# This represents force in free space, separated into +# its linear and angular parts. +Vector3 force +Vector3 torque diff --git a/spider_control/msg/geometry_msgs/msg/WrenchStamped.msg b/spider_control/msg/geometry_msgs/msg/WrenchStamped.msg new file mode 100644 index 0000000000000000000000000000000000000000..dad910ed724de005e89e3422ef1ca7cec401e9e4 --- /dev/null +++ b/spider_control/msg/geometry_msgs/msg/WrenchStamped.msg @@ -0,0 +1,3 @@ +# A wrench with reference coordinate frame and timestamp +Header header +Wrench wrench diff --git a/spider_control/msg/geometry_msgs/package.xml b/spider_control/msg/geometry_msgs/package.xml new file mode 100644 index 0000000000000000000000000000000000000000..f718c268316cb78b4795f8ded3aab13e71c8d29b --- /dev/null +++ b/spider_control/msg/geometry_msgs/package.xml @@ -0,0 +1,27 @@ + + geometry_msgs + 1.12.7 + + geometry_msgs provides messages for common geometric primitives + such as points, vectors, and poses. These primitives are designed + to provide a common data type and facilitate interoperability + throughout the system. + + Tully Foote + BSD + + http://wiki.ros.org/geometry_msgs + Tully Foote + + catkin + + message_generation + std_msgs + + message_runtime + std_msgs + + + + + diff --git a/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake b/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake new file mode 100644 index 0000000000000000000000000000000000000000..9024495695453d754f782a61853091fee8e042e7 --- /dev/null +++ b/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake @@ -0,0 +1,2 @@ +set(sensor_msgs_MESSAGE_FILES "msg/BatteryState.msg;msg/CameraInfo.msg;msg/ChannelFloat32.msg;msg/CompressedImage.msg;msg/FluidPressure.msg;msg/Illuminance.msg;msg/Image.msg;msg/Imu.msg;msg/JointState.msg;msg/Joy.msg;msg/JoyFeedback.msg;msg/JoyFeedbackArray.msg;msg/LaserEcho.msg;msg/LaserScan.msg;msg/MagneticField.msg;msg/MultiDOFJointState.msg;msg/MultiEchoLaserScan.msg;msg/NavSatFix.msg;msg/NavSatStatus.msg;msg/PointCloud.msg;msg/PointCloud2.msg;msg/PointField.msg;msg/Range.msg;msg/RegionOfInterest.msg;msg/RelativeHumidity.msg;msg/Temperature.msg;msg/TimeReference.msg") +set(sensor_msgs_SERVICE_FILES "srv/SetCameraInfo.srv") diff --git a/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-paths.cmake b/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-paths.cmake new file mode 100644 index 0000000000000000000000000000000000000000..3ccd3cfa6298a5bb4bb51f48fe02699814c78db9 --- /dev/null +++ b/spider_control/msg/sensor_msgs/cmake/sensor_msgs-msg-paths.cmake @@ -0,0 +1,4 @@ +# generated from genmsg/cmake/pkg-msg-paths.cmake.installspace.in + +_prepend_path("${sensor_msgs_DIR}/.." "msg" sensor_msgs_MSG_INCLUDE_DIRS UNIQUE) +set(sensor_msgs_MSG_DEPENDENCIES geometry_msgs;std_msgs) diff --git a/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig-version.cmake b/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig-version.cmake new file mode 100644 index 0000000000000000000000000000000000000000..20c93291af12ed54520d694ebacc76df45fa6e0f --- /dev/null +++ b/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig-version.cmake @@ -0,0 +1,14 @@ +# generated from catkin/cmake/template/pkgConfig-version.cmake.in +set(PACKAGE_VERSION "1.12.7") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig.cmake b/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig.cmake new file mode 100644 index 0000000000000000000000000000000000000000..324db04504dd5bb826beaa776e8abf27bfc25bfb --- /dev/null +++ b/spider_control/msg/sensor_msgs/cmake/sensor_msgsConfig.cmake @@ -0,0 +1,200 @@ +# generated from catkin/cmake/template/pkgConfig.cmake.in + +# append elements to a list and remove existing duplicates from the list +# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig +# self contained +macro(_list_append_deduplicate listname) + if(NOT "${ARGN}" STREQUAL "") + if(${listname}) + list(REMOVE_ITEM ${listname} ${ARGN}) + endif() + list(APPEND ${listname} ${ARGN}) + endif() +endmacro() + +# append elements to a list if they are not already in the list +# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig +# self contained +macro(_list_append_unique listname) + foreach(_item ${ARGN}) + list(FIND ${listname} ${_item} _index) + if(_index EQUAL -1) + list(APPEND ${listname} ${_item}) + endif() + endforeach() +endmacro() + +# pack a list of libraries with optional build configuration keywords +# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig +# self contained +macro(_pack_libraries_with_build_configuration VAR) + set(${VAR} "") + set(_argn ${ARGN}) + list(LENGTH _argn _count) + set(_index 0) + while(${_index} LESS ${_count}) + list(GET _argn ${_index} lib) + if("${lib}" MATCHES "^(debug|optimized|general)$") + math(EXPR _index "${_index} + 1") + if(${_index} EQUAL ${_count}) + message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library") + endif() + list(GET _argn ${_index} library) + list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}") + else() + list(APPEND ${VAR} "${lib}") + endif() + math(EXPR _index "${_index} + 1") + endwhile() +endmacro() + +# unpack a list of libraries with optional build configuration keyword prefixes +# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig +# self contained +macro(_unpack_libraries_with_build_configuration VAR) + set(${VAR} "") + foreach(lib ${ARGN}) + string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}") + list(APPEND ${VAR} "${lib}") + endforeach() +endmacro() + + +if(sensor_msgs_CONFIG_INCLUDED) + return() +endif() +set(sensor_msgs_CONFIG_INCLUDED TRUE) + +# set variables for source/devel/install prefixes +if("FALSE" STREQUAL "TRUE") + set(sensor_msgs_SOURCE_PREFIX /tmp/binarydeb/ros-melodic-sensor-msgs-1.12.7) + set(sensor_msgs_DEVEL_PREFIX /tmp/binarydeb/ros-melodic-sensor-msgs-1.12.7/obj-x86_64-linux-gnu/devel) + set(sensor_msgs_INSTALL_PREFIX "") + set(sensor_msgs_PREFIX ${sensor_msgs_DEVEL_PREFIX}) +else() + set(sensor_msgs_SOURCE_PREFIX "") + set(sensor_msgs_DEVEL_PREFIX "") + set(sensor_msgs_INSTALL_PREFIX /opt/ros/melodic) + set(sensor_msgs_PREFIX ${sensor_msgs_INSTALL_PREFIX}) +endif() + +# warn when using a deprecated package +if(NOT "" STREQUAL "") + set(_msg "WARNING: package 'sensor_msgs' is deprecated") + # append custom deprecation text if available + if(NOT "" STREQUAL "TRUE") + set(_msg "${_msg} ()") + endif() + message("${_msg}") +endif() + +# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project +set(sensor_msgs_FOUND_CATKIN_PROJECT TRUE) + +if(NOT "include " STREQUAL " ") + set(sensor_msgs_INCLUDE_DIRS "") + set(_include_dirs "include") + if(NOT " " STREQUAL " ") + set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.") + elseif(NOT "http://ros.org/wiki/sensor_msgs " STREQUAL " ") + set(_report "Check the website 'http://ros.org/wiki/sensor_msgs' for information and consider reporting the problem.") + else() + set(_report "Report the problem to the maintainer 'Tully Foote ' and request to fix the problem.") + endif() + foreach(idir ${_include_dirs}) + if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir}) + set(include ${idir}) + elseif("${idir} " STREQUAL "include ") + get_filename_component(include "${sensor_msgs_DIR}/../../../include" ABSOLUTE) + if(NOT IS_DIRECTORY ${include}) + message(FATAL_ERROR "Project 'sensor_msgs' specifies '${idir}' as an include dir, which is not found. It does not exist in '${include}'. ${_report}") + endif() + else() + message(FATAL_ERROR "Project 'sensor_msgs' specifies '${idir}' as an include dir, which is not found. It does neither exist as an absolute directory nor in '/opt/ros/melodic/${idir}'. ${_report}") + endif() + _list_append_unique(sensor_msgs_INCLUDE_DIRS ${include}) + endforeach() +endif() + +set(libraries "") +foreach(library ${libraries}) + # keep build configuration keywords, target names and absolute libraries as-is + if("${library}" MATCHES "^(debug|optimized|general)$") + list(APPEND sensor_msgs_LIBRARIES ${library}) + elseif(${library} MATCHES "^-l") + list(APPEND sensor_msgs_LIBRARIES ${library}) + elseif(TARGET ${library}) + list(APPEND sensor_msgs_LIBRARIES ${library}) + elseif(IS_ABSOLUTE ${library}) + list(APPEND sensor_msgs_LIBRARIES ${library}) + else() + set(lib_path "") + set(lib "${library}-NOTFOUND") + # since the path where the library is found is returned we have to iterate over the paths manually + foreach(path /opt/ros/melodic/lib;/opt/ros/melodic/lib) + find_library(lib ${library} + PATHS ${path} + NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH) + if(lib) + set(lib_path ${path}) + break() + endif() + endforeach() + if(lib) + _list_append_unique(sensor_msgs_LIBRARY_DIRS ${lib_path}) + list(APPEND sensor_msgs_LIBRARIES ${lib}) + else() + # as a fall back for non-catkin libraries try to search globally + find_library(lib ${library}) + if(NOT lib) + message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'. The library is neither a target nor built/installed properly. Did you compile project 'sensor_msgs'? Did you find_package() it before the subdirectory containing its code is included?") + endif() + list(APPEND sensor_msgs_LIBRARIES ${lib}) + endif() + endif() +endforeach() + +set(sensor_msgs_EXPORTED_TARGETS "sensor_msgs_generate_messages_cpp;sensor_msgs_generate_messages_eus;sensor_msgs_generate_messages_lisp;sensor_msgs_generate_messages_nodejs;sensor_msgs_generate_messages_py") +# create dummy targets for exported code generation targets to make life of users easier +foreach(t ${sensor_msgs_EXPORTED_TARGETS}) + if(NOT TARGET ${t}) + add_custom_target(${t}) + endif() +endforeach() + +set(depends "geometry_msgs;message_runtime;std_msgs") +foreach(depend ${depends}) + string(REPLACE " " ";" depend_list ${depend}) + # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls + list(GET depend_list 0 sensor_msgs_dep) + list(LENGTH depend_list count) + if(${count} EQUAL 1) + # simple dependencies must only be find_package()-ed once + if(NOT ${sensor_msgs_dep}_FOUND) + find_package(${sensor_msgs_dep} REQUIRED NO_MODULE) + endif() + else() + # dependencies with components must be find_package()-ed again + list(REMOVE_AT depend_list 0) + find_package(${sensor_msgs_dep} REQUIRED NO_MODULE ${depend_list}) + endif() + _list_append_unique(sensor_msgs_INCLUDE_DIRS ${${sensor_msgs_dep}_INCLUDE_DIRS}) + + # merge build configuration keywords with library names to correctly deduplicate + _pack_libraries_with_build_configuration(sensor_msgs_LIBRARIES ${sensor_msgs_LIBRARIES}) + _pack_libraries_with_build_configuration(_libraries ${${sensor_msgs_dep}_LIBRARIES}) + _list_append_deduplicate(sensor_msgs_LIBRARIES ${_libraries}) + # undo build configuration keyword merging after deduplication + _unpack_libraries_with_build_configuration(sensor_msgs_LIBRARIES ${sensor_msgs_LIBRARIES}) + + _list_append_unique(sensor_msgs_LIBRARY_DIRS ${${sensor_msgs_dep}_LIBRARY_DIRS}) + list(APPEND sensor_msgs_EXPORTED_TARGETS ${${sensor_msgs_dep}_EXPORTED_TARGETS}) +endforeach() + +set(pkg_cfg_extras "sensor_msgs-msg-extras.cmake") +foreach(extra ${pkg_cfg_extras}) + if(NOT IS_ABSOLUTE ${extra}) + set(extra ${sensor_msgs_DIR}/${extra}) + endif() + include(${extra}) +endforeach() diff --git a/spider_control/msg/sensor_msgs/migration_rules/sensor_msgs.bmr b/spider_control/msg/sensor_msgs/migration_rules/sensor_msgs.bmr new file mode 100644 index 0000000000000000000000000000000000000000..59405bb6fe30fe5c0d606ef6e62018d43170ad0e --- /dev/null +++ b/spider_control/msg/sensor_msgs/migration_rules/sensor_msgs.bmr @@ -0,0 +1,1756 @@ +class update_robot_msgs_PointCloud_c47b5cedd2b77d241b27547ed7624840(MessageUpdateRule): + old_type = "robot_msgs/PointCloud" + old_full_text = """ +Header header +Point32[] pts +ChannelFloat32[] chan + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: robot_msgs/Point32 +float32 x +float32 y +float32 z +================================================================================ +MSG: robot_msgs/ChannelFloat32 +string name +float32[] vals +""" + + new_type = "sensor_msgs/PointCloud" + new_full_text = """ +Header header +geometry_msgs/Point32[] points +ChannelFloat32[] channels + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: geometry_msgs/Point32 +float32 x +float32 y +float32 z +================================================================================ +MSG: sensor_msgs/ChannelFloat32 +string name +float32[] values +""" + + order = 0 + migrated_types = [ + ("Header","Header"), + ("Point32","geometry_msgs/Point32"), + ("ChannelFloat32","ChannelFloat32")] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + self.migrate_array(old_msg.pts, new_msg.points, "geometry_msgs/Point32") + self.migrate_array(old_msg.chan, new_msg.channels, "ChannelFloat32") + + +class update_robot_msgs_ChannelFloat32_61c47e4621e471c885edb248b5dcafd5(MessageUpdateRule): + old_type = "robot_msgs/ChannelFloat32" + old_full_text = """ +string name +float32[] vals +""" + + new_type = "sensor_msgs/ChannelFloat32" + new_full_text = """ +string name +float32[] values +""" + + order = 0 + migrated_types = [] + + valid = True + + def update(self, old_msg, new_msg): + new_msg.name = old_msg.name + new_msg.values = old_msg.vals + + + + + +class update_image_msgs_CamInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule): + old_type = "image_msgs/CamInfo" + old_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace and accompanied by up to 5 image topics named: +# +# image_raw, image, image_color, image_rect, and image_rect_color + +Header header + +uint32 height +uint32 width + +float64[5] D # Distortion: k1, k2, t1, t2, k3 +float64[9] K # original camera matrix +float64[9] R # rectification matrix +float64[12] P # projection/camera matrix + +# Should put exposure, gain, etc. information here as well + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + new_type = "sensor_msgs/CameraInfo" + new_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace and accompanied by up to 5 image topics named: +# +# image_raw, image, image_color, image_rect, and image_rect_color +# +# The meaning of the camera parameters are described in detail at +# http://pr.willowgarage.com/wiki/Camera_Calibration. + +Header header + +# Resolution in pixels +uint32 height +uint32 width + +######################## +# Intrinsic parameters # +######################## + +# Distortion parameters: k1, k2, t1, t2, k3 +# These model radial and tangential distortion of the camera. +float64[5] D # 5x1 vector + +# Original camera matrix +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy): +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +float64[9] K # 3x3 row-major matrix + +######################## +# Extrinsic parameters # +######################## + +# Rectification matrix (stereo cameras only) +# A homography which takes an image to the ideal stereo image plane +# so that epipolar lines in both stereo images are parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# Projects 3D points in a world coordinate frame to 2D pixel coordinates. +float64[12] P # 3x4 row-major matrix + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.height = old_msg.height + new_msg.width = old_msg.width + new_msg.D = old_msg.D + new_msg.K = old_msg.K + new_msg.R = old_msg.R + new_msg.P = old_msg.P + + +class update_sensor_msgs_CameraInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule): + + old_type = "sensor_msgs/CameraInfo" + old_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace and accompanied by up to 5 image topics named: +# +# image_raw, image, image_color, image_rect, and image_rect_color +# +# The meaning of the camera parameters are described in detail at +# http://pr.willowgarage.com/wiki/Camera_Calibration. + +Header header + +# Resolution in pixels +uint32 height +uint32 width + +######################## +# Intrinsic parameters # +######################## + +# Distortion parameters: k1, k2, t1, t2, k3 +# These model radial and tangential distortion of the camera. +float64[5] D # 5x1 vector + +# Original camera matrix +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy): +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +float64[9] K # 3x3 row-major matrix + +######################## +# Extrinsic parameters # +######################## + +# Rectification matrix (stereo cameras only) +# A homography which takes an image to the ideal stereo image plane +# so that epipolar lines in both stereo images are parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# Projects 3D points in a world coordinate frame to 2D pixel coordinates. +float64[12] P # 3x4 row-major matrix + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + new_type = "sensor_msgs/CameraInfo" + new_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace and accompanied by up to 5 image topics named: +# +# image_raw, image, image_color, image_rect, and image_rect_color +# +# The meaning of the camera parameters are described in detail at +# http://pr.willowgarage.com/wiki/Camera_Calibration. + +########################## +# Image acquisition info # +########################## + +# Time of image acquisition, camera coordinate frame ID +Header header + +# Camera resolution in pixels +uint32 height +uint32 width + +# Region of interest (subwindow of full camera resolution), if applicable +RegionOfInterest roi + +######################## +# Intrinsic parameters # +######################## + +# Distortion parameters: k1, k2, t1, t2, k3 +# These model radial and tangential distortion of the camera. +float64[5] D # 5x1 vector + +# Original camera matrix +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy): +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +float64[9] K # 3x3 row-major matrix + +######################## +# Extrinsic parameters # +######################## + +# Rectification matrix (stereo cameras only) +# A homography which takes an image to the ideal stereo image plane +# so that epipolar lines in both stereo images are parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# Projects 3D points in a world coordinate frame to 2D pixel coordinates. +float64[12] P # 3x4 row-major matrix + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: sensor_msgs/RegionOfInterest +uint32 x_offset +uint32 y_offset +uint32 height +uint32 width +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.height = old_msg.height + new_msg.width = old_msg.width + new_msg.roi = self.get_new_class('sensor_msgs/RegionOfInterest')(0,0,old_msg.height,old_msg.width) + new_msg.D = old_msg.D + new_msg.K = old_msg.K + new_msg.R = old_msg.R + new_msg.P = old_msg.P + + +class update_sensor_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule): + old_type = "sensor_msgs/Image" + old_full_text = """ +Header header # Header +string label # Label for the image +string encoding # Specifies the color encoding of the data + # Acceptable values are: + # 1 channel types: + # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr + # 3 channel types: + # rgb, bgr + # 4 channel types: + # rgba, bgra, yuv422 + # 6 channel types: + # yuv411 + # N channel types: + # other +string depth # Specifies the depth of the data: + # Acceptable values: + # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 + +# Based on depth ONE of the following MultiArrays may contain data. +# The multi-array MUST have 3 dimensions, labeled as "height", +# "width", and "channel", though depending on usage the ordering of +# the dimensions may very. Note that IPL Image convention will order +# these as: height, width, channel, which is the preferred ordering +# unless performance dictates otherwise. +# +# Height, width, and number of channels are specified in the dimension +# sizes within the appropriate MultiArray + +std_msgs/UInt8MultiArray uint8_data +std_msgs/Int8MultiArray int8_data +std_msgs/UInt16MultiArray uint16_data +std_msgs/Int16MultiArray int16_data +std_msgs/UInt32MultiArray uint32_data +std_msgs/Int32MultiArray int32_data +std_msgs/UInt64MultiArray uint64_data +std_msgs/Int64MultiArray int64_data +std_msgs/Float32MultiArray float32_data +std_msgs/Float64MultiArray float64_data + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: std_msgs/UInt8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data + + +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/Int8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int8[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint16[] data # array of data + + +================================================================================ +MSG: std_msgs/Int16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int16[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint32[] data # array of data + + +================================================================================ +MSG: std_msgs/Int32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int32[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint64[] data # array of data + + +================================================================================ +MSG: std_msgs/Int64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int64[] data # array of data + + +================================================================================ +MSG: std_msgs/Float32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float32[] data # array of data + + +================================================================================ +MSG: std_msgs/Float64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float64[] data # array of data +""" + + new_type = "sensor_msgs/Image" + new_full_text = """ +Header header # Header + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file src/image_encodings.cpp +# If you want to standardize a new string format, join ros-users@lists.sourceforge.net and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size -- taken from the list of strings in src/image_encodings.cpp +uint8 is_bigendian # is this data bigendian +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + + def update_empty(self, old_msg, new_msg): + pass + + def update_mono_uint8(self, old_msg, new_msg): + assert (len(old_msg.uint8_data.layout.dim) == 3 and + old_msg.uint8_data.layout.dim[0].label == 'height' and + old_msg.uint8_data.layout.dim[1].label == 'width' and + old_msg.uint8_data.layout.dim[2].label == 'channel'), \ + 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' + + self.migrate(old_msg.header, new_msg.header) + new_msg.encoding = 'mono8' + new_msg.step = old_msg.uint8_data.layout.dim[1].stride + new_msg.data = old_msg.uint8_data.data + new_msg.height = old_msg.uint8_data.layout.dim[0].size + new_msg.width = old_msg.uint8_data.layout.dim[1].size + new_msg.is_bigendian = 0 + + def update_rgb_uint8(self, old_msg, new_msg): + assert (len(old_msg.uint8_data.layout.dim) == 3 and + old_msg.uint8_data.layout.dim[0].label == 'height' and + old_msg.uint8_data.layout.dim[1].label == 'width' and + old_msg.uint8_data.layout.dim[2].label == 'channel'), \ + 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' + + self.migrate(old_msg.header, new_msg.header) + new_msg.encoding = 'rgb8' + new_msg.step = old_msg.uint8_data.layout.dim[1].stride + new_msg.data = old_msg.uint8_data.data + new_msg.height = old_msg.uint8_data.layout.dim[0].size + new_msg.width = old_msg.uint8_data.layout.dim[1].size + new_msg.is_bigendian = 0 + + def update_bgr_uint8(self, old_msg, new_msg): + assert (len(old_msg.uint8_data.layout.dim) == 3 and + old_msg.uint8_data.layout.dim[0].label == 'height' and + old_msg.uint8_data.layout.dim[1].label == 'width' and + old_msg.uint8_data.layout.dim[2].label == 'channel'), \ + 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' + + self.migrate(old_msg.header, new_msg.header) + new_msg.encoding = 'bgr8' + new_msg.step = old_msg.uint8_data.layout.dim[1].stride + new_msg.data = old_msg.uint8_data.data + new_msg.height = old_msg.uint8_data.layout.dim[0].size + new_msg.width = old_msg.uint8_data.layout.dim[1].size + new_msg.is_bigendian = 0 + + def update(self, old_msg, new_msg): + encoding_map = {('',''): self.update_empty, + ('other','none'): self.update_empty, + ('mono', 'uint8'): self.update_mono_uint8, + ('rgb', 'uint8'): self.update_rgb_uint8, + ('bgr', 'uint8'): self.update_bgr_uint8} + key = (old_msg.encoding, old_msg.depth) + + assert key in encoding_map, 'This rule does not support migrating from %s %s'%key + + encoding_map[key](old_msg, new_msg) + + + + + +class update_image_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule): + old_type = "image_msgs/Image" + old_full_text = """ +Header header # Header +string label # Label for the image +string encoding # Specifies the color encoding of the data + # Acceptable values are: + # 1 channel types: + # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr + # 3 channel types: + # rgb, bgr + # 4 channel types: + # rgba, bgra, yuv422 + # 6 channel types: + # yuv411 + # N channel types: + # other +string depth # Specifies the depth of the data: + # Acceptable values: + # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 + +# Based on depth ONE of the following MultiArrays may contain data. +# The multi-array MUST have 3 dimensions, labeled as "height", +# "width", and "channel", though depending on usage the ordering of +# the dimensions may very. Note that IPL Image convention will order +# these as: height, width, channel, which is the preferred ordering +# unless performance dictates otherwise. +# +# Height, width, and number of channels are specified in the dimension +# sizes within the appropriate MultiArray + +std_msgs/UInt8MultiArray uint8_data +std_msgs/Int8MultiArray int8_data +std_msgs/UInt16MultiArray uint16_data +std_msgs/Int16MultiArray int16_data +std_msgs/UInt32MultiArray uint32_data +std_msgs/Int32MultiArray int32_data +std_msgs/UInt64MultiArray uint64_data +std_msgs/Int64MultiArray int64_data +std_msgs/Float32MultiArray float32_data +std_msgs/Float64MultiArray float64_data + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: std_msgs/UInt8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data + + +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/Int8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int8[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint16[] data # array of data + + +================================================================================ +MSG: std_msgs/Int16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int16[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint32[] data # array of data + + +================================================================================ +MSG: std_msgs/Int32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int32[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint64[] data # array of data + + +================================================================================ +MSG: std_msgs/Int64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int64[] data # array of data + + +================================================================================ +MSG: std_msgs/Float32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float32[] data # array of data + + +================================================================================ +MSG: std_msgs/Float64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float64[] data # array of data +""" + + + new_type = "sensor_msgs/Image" + new_full_text = """ +Header header # Header +string label # Label for the image +string encoding # Specifies the color encoding of the data + # Acceptable values are: + # 1 channel types: + # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr + # 3 channel types: + # rgb, bgr + # 4 channel types: + # rgba, bgra, yuv422 + # 6 channel types: + # yuv411 + # N channel types: + # other +string depth # Specifies the depth of the data: + # Acceptable values: + # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 + +# Based on depth ONE of the following MultiArrays may contain data. +# The multi-array MUST have 3 dimensions, labeled as "height", +# "width", and "channel", though depending on usage the ordering of +# the dimensions may very. Note that IPL Image convention will order +# these as: height, width, channel, which is the preferred ordering +# unless performance dictates otherwise. +# +# Height, width, and number of channels are specified in the dimension +# sizes within the appropriate MultiArray + +std_msgs/UInt8MultiArray uint8_data +std_msgs/Int8MultiArray int8_data +std_msgs/UInt16MultiArray uint16_data +std_msgs/Int16MultiArray int16_data +std_msgs/UInt32MultiArray uint32_data +std_msgs/Int32MultiArray int32_data +std_msgs/UInt64MultiArray uint64_data +std_msgs/Int64MultiArray int64_data +std_msgs/Float32MultiArray float32_data +std_msgs/Float64MultiArray float64_data + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: std_msgs/UInt8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data + + +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/Int8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int8[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint16[] data # array of data + + +================================================================================ +MSG: std_msgs/Int16MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int16[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint32[] data # array of data + + +================================================================================ +MSG: std_msgs/Int32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int32[] data # array of data + + +================================================================================ +MSG: std_msgs/UInt64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint64[] data # array of data + + +================================================================================ +MSG: std_msgs/Int64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int64[] data # array of data + + +================================================================================ +MSG: std_msgs/Float32MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float32[] data # array of data + + +================================================================================ +MSG: std_msgs/Float64MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float64[] data # array of data +""" + + order = 0 + migrated_types = [ + ("Header","Header"), + ("Image","Image")] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg, new_msg) + + + + +class update_sensor_msgs_CompressedImage_9f25a34569b1b807704b985d4396ad35(MessageUpdateRule): + old_type = "sensor_msgs/CompressedImage" + old_full_text = """ +Header header # Header +string label # Label for the image +string encoding # Specifies the color encoding of the data + # Acceptable values are: + # 1 channel types: + # mono + # 3 channel types: + # rgb, bgr +string format # Specifies the format of the data + # Acceptable values: + # jpeg + +std_msgs/UInt8MultiArray uint8_data + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: std_msgs/UInt8MultiArray +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data + + +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +""" + + new_type = "sensor_msgs/CompressedImage" + new_full_text = """ +Header header # Header +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png +uint8[] data # Compressed image buffer + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.format = old_msg.format + new_msg.data = old_msg.uint8_data.data + +class update_laser_scan_LaserScan_90c7ef2dc6895d81024acba2ac42f369(MessageUpdateRule): + old_type = "laser_scan/LaserScan" + old_full_text = """ +# +# Laser scans angles are measured counter clockwise, with 0 facing forward +# (along the x-axis) of the device frame +# + +Header header +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] +float32 time_increment # time between measurements [seconds] +float32 scan_time # time between scans [seconds] +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] +float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units] + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + new_type = "sensor_msgs/LaserScan" + new_full_text = """ +# Single scan from a planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, laser is assumed to spin around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.angle_min = old_msg.angle_min + new_msg.angle_max = old_msg.angle_max + new_msg.angle_increment = old_msg.angle_increment + new_msg.time_increment = old_msg.time_increment + new_msg.scan_time = old_msg.scan_time + new_msg.range_min = old_msg.range_min + new_msg.range_max = old_msg.range_max + new_msg.ranges = old_msg.ranges + new_msg.intensities = old_msg.intensities + +class update_mechanism_msgs_JointStates_6def7c223229ab1e340258092e485703(MessageUpdateRule): + old_type = "mechanism_msgs/JointStates" + old_full_text = """ +Header header +mechanism_msgs/JointState[] joints + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: mechanism_msgs/JointState +string name +float64 position +float64 velocity +float64 applied_effort +float64 commanded_effort +byte is_calibrated +""" + + new_type = "sensor_msgs/JointState" + new_full_text = """ +Header header + +string[] name +float64[] position +float64[] velocity +float64[] effort + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id +""" + + order = 0 + migrated_types = [ + ("Header","Header"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.name = [j.name for j in old_msg.joints] + new_msg.position = [j.position for j in old_msg.joints] + new_msg.velocity = [j.velocity for j in old_msg.joints] + new_msg.effort = [j.applied_effort for j in old_msg.joints] + +class update_sensor_msgs_PointCloud_c47b5cedd2b77d241b27547ed7624840(MessageUpdateRule): + old_type = "sensor_msgs/PointCloud" + old_full_text = """ +Header header +geometry_msgs/Point32[] pts +ChannelFloat32[] chan + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: geometry_msgs/Point32 +float32 x +float32 y +float32 z +================================================================================ +MSG: sensor_msgs/ChannelFloat32 +string name +float32[] vals +""" + + new_type = "sensor_msgs/PointCloud" + new_full_text = """ +#This message holds a collection of 3d points, plus optional additional information about each point. +#Each Point32 should be interpreted as a 3d point in the frame given in the header + +Header header +geometry_msgs/Point32[] points #Array of 3d points +ChannelFloat32[] channels #Each channel should have the same number of elements as points array, and the data in each channel should correspond 1:1 with each point + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: sensor_msgs/ChannelFloat32 +#This message is used by the PointCloud message to hold optional data associated with each point in the cloud +#The length of the values array should be the same as the length of the points array in the PointCloud, and each value should be associated with the corresponding point + +string name #channel name should give semantics of the channel (e.g. "intensity" instead of "value") +float32[] values #values array should have same number of elements as the associated PointCloud +""" + + order = 0 + migrated_types = [ + ("Header","Header"), + ("geometry_msgs/Point32","geometry_msgs/Point32"), + ("ChannelFloat32","ChannelFloat32")] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + self.migrate_array(old_msg.pts, new_msg.points, "geometry_msgs/Point32") + self.migrate_array(old_msg.chan, new_msg.channels, "ChannelFloat32") + +class update_sensor_msgs_ChannelFloat32_61c47e4621e471c885edb248b5dcafd5(MessageUpdateRule): + old_type = "sensor_msgs/ChannelFloat32" + old_full_text = """ +string name +float32[] vals +""" + + new_type = "sensor_msgs/ChannelFloat32" + new_full_text = """ +#This message is used by the PointCloud message to hold optional data associated with each point in the cloud +#The length of the values array should be the same as the length of the points array in the PointCloud, and each value should be associated with the corresponding point + +string name #channel name should give semantics of the channel (e.g. "intensity" instead of "value") +float32[] values #values array should have same number of elements as the associated PointCloud +""" + + order = 0 + migrated_types = [] + + valid = True + + def update(self, old_msg, new_msg): + new_msg.name = old_msg.name + new_msg.values = old_msg.vals + +class update_sensor_msgs_CameraInfo_1b5cf7f984c229b6141ceb3a955aa18f(MessageUpdateRule): + old_type = "sensor_msgs/CameraInfo" + old_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace and accompanied by up to 5 image topics named: +# +# image_raw, image, image_color, image_rect, and image_rect_color +# +# The meaning of the camera parameters are described in detail at +# http://pr.willowgarage.com/wiki/Camera_Calibration. + +########################## +# Image acquisition info # +########################## + +# Time of image acquisition, camera coordinate frame ID +Header header + +# Camera resolution in pixels +uint32 height +uint32 width + +# Region of interest (subwindow of full camera resolution), if applicable +RegionOfInterest roi + +######################## +# Intrinsic parameters # +######################## + +# Distortion parameters: k1, k2, t1, t2, k3 +# These model radial and tangential distortion of the camera. +float64[5] D # 5x1 vector + +# Original camera matrix +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy): +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +float64[9] K # 3x3 row-major matrix + +######################## +# Extrinsic parameters # +######################## + +# Rectification matrix (stereo cameras only) +# A homography which takes an image to the ideal stereo image plane +# so that epipolar lines in both stereo images are parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# Projects 3D points in a world coordinate frame to 2D pixel coordinates. +float64[12] P # 3x4 row-major matrix + +================================================================================ +MSG: roslib/Header +#Standard metadata for higher-level flow data types +#sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: sensor_msgs/RegionOfInterest +uint32 x_offset +uint32 y_offset +uint32 height +uint32 width +""" + + new_type = "sensor_msgs/CameraInfo" + new_full_text = """ +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. Normally +# this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficent. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] D + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] K # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] P # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi + +================================================================================ +MSG: roslib/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.secs: seconds (stamp_secs) since epoch +# * stamp.nsecs: nanoseconds since stamp_secs +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +# 0: no frame +# 1: global frame +string frame_id + +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +""" + + order = 1 + migrated_types = [ + ("Header","Header"), + ("RegionOfInterest","RegionOfInterest"),] + + valid = True + + def update(self, old_msg, new_msg): + self.migrate(old_msg.header, new_msg.header) + new_msg.height = old_msg.height + new_msg.width = old_msg.width + #No matching field name in old message + new_msg.distortion_model = 'plumb_bob' + #Converted from fixed array of length 5 to variable length + new_msg.D = old_msg.D + new_msg.K = old_msg.K + new_msg.R = old_msg.R + new_msg.P = old_msg.P + #No matching field name in old message + new_msg.binning_x = 1 + #No matching field name in old message + new_msg.binning_y = 1 + self.migrate(old_msg.roi, new_msg.roi) + # Set do_rectify True if ROI is not full resolution + new_msg.roi.do_rectify = (new_msg.roi.width > 0 and new_msg.roi.width < new_msg.width) or \ + (new_msg.roi.height > 0 and new_msg.roi.height < new_msg.height) +class update_sensor_msgs_RegionOfInterest_878e60591f2679769082130f7aafa371(MessageUpdateRule): + old_type = "sensor_msgs/RegionOfInterest" + old_full_text = """ +uint32 x_offset +uint32 y_offset +uint32 height +uint32 width +""" + + new_type = "sensor_msgs/RegionOfInterest" + new_full_text = """ +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +""" + + order = 0 + migrated_types = [] + + valid = True + + def update(self, old_msg, new_msg): + new_msg.x_offset = old_msg.x_offset + new_msg.y_offset = old_msg.y_offset + new_msg.height = old_msg.height + new_msg.width = old_msg.width + #No matching field name in old message + # We default to the old behavior here. do_rectify is actually set in the + # CameraInfo update rule, which knows the full-res height/width. + new_msg.do_rectify = False diff --git a/spider_control/msg/sensor_msgs/msg/BatteryState.msg b/spider_control/msg/sensor_msgs/msg/BatteryState.msg new file mode 100644 index 0000000000000000000000000000000000000000..e51dba4086469f72f22d56d2675eff31523bf104 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/BatteryState.msg @@ -0,0 +1,49 @@ + +# Constants are chosen to match the enums in the linux kernel +# defined in include/linux/power_supply.h as of version 3.7 +# The one difference is for style reasons the constants are +# all uppercase not mixed case. + +# Power supply status constants +uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 +uint8 POWER_SUPPLY_STATUS_CHARGING = 1 +uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 +uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 +uint8 POWER_SUPPLY_STATUS_FULL = 4 + +# Power supply health constants +uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 +uint8 POWER_SUPPLY_HEALTH_GOOD = 1 +uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 +uint8 POWER_SUPPLY_HEALTH_DEAD = 3 +uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 +uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 +uint8 POWER_SUPPLY_HEALTH_COLD = 6 +uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 +uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 + +# Power supply technology (chemistry) constants +uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 +uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 +uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 +uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 +uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 +uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 +uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 + +Header header +float32 voltage # Voltage in Volts (Mandatory) +float32 current # Negative when discharging (A) (If unmeasured NaN) +float32 charge # Current charge in Ah (If unmeasured NaN) +float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) +float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) +float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) +uint8 power_supply_status # The charging status as reported. Values defined above +uint8 power_supply_health # The battery health metric. Values defined above +uint8 power_supply_technology # The battery chemistry. Values defined above +bool present # True if the battery is present + +float32[] cell_voltage # An array of individual cell voltages for each cell in the pack + # If individual voltages unknown but number of cells known set each to NaN +string location # The location into which the battery is inserted. (slot number or plug) +string serial_number # The best approximation of the battery serial number diff --git a/spider_control/msg/sensor_msgs/msg/CameraInfo.msg b/spider_control/msg/sensor_msgs/msg/CameraInfo.msg new file mode 100644 index 0000000000000000000000000000000000000000..924034cfd6ab36244fbc38595c4bb7b45122d01e --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/CameraInfo.msg @@ -0,0 +1,131 @@ +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. Normally +# this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficient. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] D + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] K # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] P # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi diff --git a/spider_control/msg/sensor_msgs/msg/ChannelFloat32.msg b/spider_control/msg/sensor_msgs/msg/ChannelFloat32.msg new file mode 100644 index 0000000000000000000000000000000000000000..d2560792898958179806bfc3ec4b98712c4e73a9 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/ChannelFloat32.msg @@ -0,0 +1,24 @@ +# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. + +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values diff --git a/spider_control/msg/sensor_msgs/msg/CompressedImage.msg b/spider_control/msg/sensor_msgs/msg/CompressedImage.msg new file mode 100644 index 0000000000000000000000000000000000000000..bc9e57de3c74667e10efe7f8bf46f71f8bfb6c4b --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/CompressedImage.msg @@ -0,0 +1,13 @@ +# This message contains a compressed image + +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png +uint8[] data # Compressed image buffer diff --git a/spider_control/msg/sensor_msgs/msg/FluidPressure.msg b/spider_control/msg/sensor_msgs/msg/FluidPressure.msg new file mode 100644 index 0000000000000000000000000000000000000000..0d7c5d7d88bb1256d568a4d07f9eb878e751df36 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/FluidPressure.msg @@ -0,0 +1,12 @@ + # Single pressure reading. This message is appropriate for measuring the + # pressure inside of a fluid (air, water, etc). This also includes + # atmospheric or barometric pressure. + + # This message is not appropriate for force/pressure contact sensors. + + Header header # timestamp of the measurement + # frame_id is the location of the pressure sensor + + float64 fluid_pressure # Absolute pressure reading in Pascals. + + float64 variance # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/Illuminance.msg b/spider_control/msg/sensor_msgs/msg/Illuminance.msg new file mode 100644 index 0000000000000000000000000000000000000000..cdb4d760de54b0b6e06483d5b87e87f5eeed4faa --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Illuminance.msg @@ -0,0 +1,21 @@ + # Single photometric illuminance measurement. Light should be assumed to be + # measured along the sensor's x-axis (the area of detection is the y-z plane). + # The illuminance should have a 0 or positive value and be received with + # the sensor's +X axis pointing toward the light source. + + # Photometric illuminance is the measure of the human eye's sensitivity of the + # intensity of light encountering or passing through a surface. + + # All other Photometric and Radiometric measurements should + # not use this message. + # This message cannot represent: + # Luminous intensity (candela/light source output) + # Luminance (nits/light output per area) + # Irradiance (watt/area), etc. + + Header header # timestamp is the time the illuminance was measured + # frame_id is the location and direction of the reading + + float64 illuminance # Measurement of the Photometric Illuminance in Lux. + + float64 variance # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/Image.msg b/spider_control/msg/sensor_msgs/msg/Image.msg new file mode 100644 index 0000000000000000000000000000000000000000..68f578a0fd39d70939c540ee10eabe3dd2364cb9 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Image.msg @@ -0,0 +1,27 @@ +# This message contains an uncompressed image +# (0, 0) is at top-left corner of image +# + +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file src/image_encodings.cpp +# If you want to standardize a new string format, join +# ros-users@lists.sourceforge.net and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.h + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) diff --git a/spider_control/msg/sensor_msgs/msg/Imu.msg b/spider_control/msg/sensor_msgs/msg/Imu.msg new file mode 100644 index 0000000000000000000000000000000000000000..6a9d5322710dd5440e1b1d76e583a7dd173bd64d --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Imu.msg @@ -0,0 +1,24 @@ +# This is a message to hold data from an IMU (Inertial Measurement Unit) +# +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from the datasheet, just put those along the diagonal) +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source +# +# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation +# estimate), please set element 0 of the associated covariance matrix to -1 +# If you are interpreting this message, please check for a value of -1 in the first element of each +# covariance matrix, and disregard the associated estimate. + +Header header + +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z diff --git a/spider_control/msg/sensor_msgs/msg/JointState.msg b/spider_control/msg/sensor_msgs/msg/JointState.msg new file mode 100644 index 0000000000000000000000000000000000000000..f67f4bcf214cbf187cf5ba557f34fcbfb6966cf2 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/JointState.msg @@ -0,0 +1,26 @@ +# This is a message that holds data to describe the state of a set of torque controlled joints. +# +# The state of each joint (revolute or prismatic) is defined by: +# * the position of the joint (rad or m), +# * the velocity of the joint (rad/s or m/s) and +# * the effort that is applied in the joint (Nm or N). +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# effort associated with them, you can leave the effort array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + + +Header header + +string[] name +float64[] position +float64[] velocity +float64[] effort diff --git a/spider_control/msg/sensor_msgs/msg/Joy.msg b/spider_control/msg/sensor_msgs/msg/Joy.msg new file mode 100644 index 0000000000000000000000000000000000000000..e51cb43a792dad9b1f9c47f463e5cc1614042f89 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Joy.msg @@ -0,0 +1,4 @@ +# Reports the state of a joysticks axes and buttons. +Header header # timestamp in the header is the time the data is received from the joystick +float32[] axes # the axes measurements from a joystick +int32[] buttons # the buttons measurements from a joystick diff --git a/spider_control/msg/sensor_msgs/msg/JoyFeedback.msg b/spider_control/msg/sensor_msgs/msg/JoyFeedback.msg new file mode 100644 index 0000000000000000000000000000000000000000..9ecedab75320de59e62ca6fdf210e6825417c91d --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/JoyFeedback.msg @@ -0,0 +1,15 @@ +# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity + diff --git a/spider_control/msg/sensor_msgs/msg/JoyFeedbackArray.msg b/spider_control/msg/sensor_msgs/msg/JoyFeedbackArray.msg new file mode 100644 index 0000000000000000000000000000000000000000..9bb72b79b5a7bed2af52ebac83a458497a42a1b0 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/JoyFeedbackArray.msg @@ -0,0 +1,2 @@ +# This message publishes values for multiple feedback at once. +JoyFeedback[] array \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/LaserEcho.msg b/spider_control/msg/sensor_msgs/msg/LaserEcho.msg new file mode 100644 index 0000000000000000000000000000000000000000..11ed5fcb027b51c91a6b0193ed5b486967d93db0 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/LaserEcho.msg @@ -0,0 +1,5 @@ +# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment. \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/LaserScan.msg b/spider_control/msg/sensor_msgs/msg/LaserScan.msg new file mode 100644 index 0000000000000000000000000000000000000000..910751b8b8c5d5b96f8db07964c7865a5cc20009 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/LaserScan.msg @@ -0,0 +1,29 @@ +# Single scan from a planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. diff --git a/spider_control/msg/sensor_msgs/msg/MagneticField.msg b/spider_control/msg/sensor_msgs/msg/MagneticField.msg new file mode 100644 index 0000000000000000000000000000000000000000..dae0e22e068ccd30d0aeb65462ea0c30f40bb1a5 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/MagneticField.msg @@ -0,0 +1,22 @@ + # Measurement of the Magnetic Field vector at a specific location. + + # If the covariance of the measurement is known, it should be filled in + # (if all you know is the variance of each measurement, e.g. from the datasheet, + #just put those along the diagonal) + # A covariance matrix of all zeros will be interpreted as "covariance unknown", + # and to use the data a covariance will have to be assumed or gotten from some + # other source + + + Header header # timestamp is the time the + # field was measured + # frame_id is the location and orientation + # of the field measurement + + geometry_msgs/Vector3 magnetic_field # x, y, and z components of the + # field vector in Tesla + # If your sensor does not output 3 axes, + # put NaNs in the components not reported. + + float64[9] magnetic_field_covariance # Row major about x, y, z axes + # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/MultiDOFJointState.msg b/spider_control/msg/sensor_msgs/msg/MultiDOFJointState.msg new file mode 100644 index 0000000000000000000000000000000000000000..b5926c115df5df100e5b9f3bc7b0e174ca29df8b --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/MultiDOFJointState.msg @@ -0,0 +1,26 @@ +# Representation of state for joints with multiple degrees of freedom, +# following the structure of JointState. +# +# It is assumed that a joint in a system corresponds to a transform that gets applied +# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) +# and those 3DOF can be expressed as a transformation matrix, and that transformation +# matrix can be converted back to (x, y, yaw) +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# wrench associated with them, you can leave the wrench array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +Header header + +string[] joint_names +geometry_msgs/Transform[] transforms +geometry_msgs/Twist[] twist +geometry_msgs/Wrench[] wrench diff --git a/spider_control/msg/sensor_msgs/msg/MultiEchoLaserScan.msg b/spider_control/msg/sensor_msgs/msg/MultiEchoLaserScan.msg new file mode 100644 index 0000000000000000000000000000000000000000..02d5cc9b393b9ac44d9b2392e39920bee9074bb2 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/MultiEchoLaserScan.msg @@ -0,0 +1,31 @@ +# Single scan from a multi-echo planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded) + # +Inf measurements are out of range + # -Inf measurements are too close to determine exact distance. +LaserEcho[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/NavSatFix.msg b/spider_control/msg/sensor_msgs/msg/NavSatFix.msg new file mode 100644 index 0000000000000000000000000000000000000000..2cd817045c1ef6773e71950e0a3238a173d55115 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/NavSatFix.msg @@ -0,0 +1,46 @@ +# Navigation Satellite fix for any Global Navigation Satellite System +# +# Specified using the WGS 84 reference ellipsoid + +# header.stamp specifies the ROS time for this measurement (the +# corresponding satellite time may be reported using the +# sensor_msgs/TimeReference message). +# +# header.frame_id is the frame of reference reported by the satellite +# receiver, usually the location of the antenna. This is a +# Euclidean frame relative to the vehicle, not a reference +# ellipsoid. +Header header + +# satellite fix status information +NavSatStatus status + +# Latitude [degrees]. Positive is north of equator; negative is south. +float64 latitude + +# Longitude [degrees]. Positive is east of prime meridian; negative is west. +float64 longitude + +# Altitude [m]. Positive is above the WGS 84 ellipsoid +# (quiet NaN if no altitude is available). +float64 altitude + +# Position covariance [m^2] defined relative to a tangential plane +# through the reported position. The components are East, North, and +# Up (ENU), in row-major order. +# +# Beware: this coordinate system exhibits singularities at the poles. + +float64[9] position_covariance + +# If the covariance of the fix is known, fill it in completely. If the +# GPS receiver provides the variance of each measurement, put them +# along the diagonal. If only Dilution of Precision is available, +# estimate an approximate covariance from that. + +uint8 COVARIANCE_TYPE_UNKNOWN = 0 +uint8 COVARIANCE_TYPE_APPROXIMATED = 1 +uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 +uint8 COVARIANCE_TYPE_KNOWN = 3 + +uint8 position_covariance_type diff --git a/spider_control/msg/sensor_msgs/msg/NavSatStatus.msg b/spider_control/msg/sensor_msgs/msg/NavSatStatus.msg new file mode 100644 index 0000000000000000000000000000000000000000..4fce76f23d23c6e7f2ceea2f4c34014da8021d34 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/NavSatStatus.msg @@ -0,0 +1,22 @@ +# Navigation Satellite fix status for any Global Navigation Satellite System + +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service diff --git a/spider_control/msg/sensor_msgs/msg/PointCloud.msg b/spider_control/msg/sensor_msgs/msg/PointCloud.msg new file mode 100644 index 0000000000000000000000000000000000000000..a0eac50c6deb978502181896f4a99eef90f960a7 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/PointCloud.msg @@ -0,0 +1,14 @@ +# This message holds a collection of 3d points, plus optional additional +# information about each point. + +# Time of sensor data acquisition, coordinate frame ID. +Header header + +# Array of 3d points. Each Point32 should be interpreted as a 3d point +# in the frame given in the header. +geometry_msgs/Point32[] points + +# Each channel should have the same number of elements as points array, +# and the data in each channel should correspond 1:1 with each point. +# Channel names in common practice are listed in ChannelFloat32.msg. +ChannelFloat32[] channels diff --git a/spider_control/msg/sensor_msgs/msg/PointCloud2.msg b/spider_control/msg/sensor_msgs/msg/PointCloud2.msg new file mode 100644 index 0000000000000000000000000000000000000000..69a9302a2a10d22b52f0bc3344d98ad27b784f13 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/PointCloud2.msg @@ -0,0 +1,27 @@ +# This message holds a collection of N-dimensional points, which may +# contain additional information such as normals, intensity, etc. The +# point data is stored as a binary blob, its layout described by the +# contents of the "fields" array. + +# The point cloud data may be organized 2d (image-like) or 1d +# (unordered). Point clouds organized as 2d images may be produced by +# camera depth sensors such as stereo or time-of-flight. + +# Time of sensor data acquisition, and the coordinate frame ID (for 3d +# points). +Header header + +# 2D structure of the point cloud. If the cloud is unordered, height is +# 1 and width is the length of the point cloud. +uint32 height +uint32 width + +# Describes the channels and their layout in the binary data blob. +PointField[] fields + +bool is_bigendian # Is this data bigendian? +uint32 point_step # Length of a point in bytes +uint32 row_step # Length of a row in bytes +uint8[] data # Actual point data, size is (row_step*height) + +bool is_dense # True if there are no invalid points diff --git a/spider_control/msg/sensor_msgs/msg/PointField.msg b/spider_control/msg/sensor_msgs/msg/PointField.msg new file mode 100644 index 0000000000000000000000000000000000000000..fb9ff5453f772608066466358c77b742f8d84174 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/PointField.msg @@ -0,0 +1,15 @@ +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field diff --git a/spider_control/msg/sensor_msgs/msg/Range.msg b/spider_control/msg/sensor_msgs/msg/Range.msg new file mode 100644 index 0000000000000000000000000000000000000000..5493652ad8fbca99fe068e4010eeed0748f67395 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Range.msg @@ -0,0 +1,40 @@ +# Single range reading from an active ranger that emits energy and reports +# one range reading that is valid along an arc at the distance measured. +# This message is not appropriate for laser scanners. See the LaserScan +# message if you are working with a laser scanner. + +# This message also can represent a fixed-distance (binary) ranger. This +# sensor will have min_range===max_range===distance of detection. +# These sensors follow REP 117 and will output -Inf if the object is detected +# and +Inf if the object is outside of the detection range. + +Header header # timestamp in the header is the time the ranger + # returned the distance reading + +# Radiation type enums +# If you want a value added to this list, send an email to the ros-users list +uint8 ULTRASOUND=0 +uint8 INFRARED=1 + +uint8 radiation_type # the type of radiation used by the sensor + # (sound, IR, etc) [enum] + +float32 field_of_view # the size of the arc that the distance reading is + # valid for [rad] + # the object causing the range reading may have + # been anywhere within -field_of_view/2 and + # field_of_view/2 at the measured range. + # 0 angle corresponds to the x-axis of the sensor. + +float32 min_range # minimum range value [m] +float32 max_range # maximum range value [m] + # Fixed distance rangers require min_range==max_range + +float32 range # range data [m] + # (Note: values < range_min or > range_max + # should be discarded) + # Fixed distance rangers only output -Inf or +Inf. + # -Inf represents a detection within fixed distance. + # (Detection too close to the sensor to quantify) + # +Inf represents no detection within the fixed distance. + # (Object out of range) \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/RegionOfInterest.msg b/spider_control/msg/sensor_msgs/msg/RegionOfInterest.msg new file mode 100644 index 0000000000000000000000000000000000000000..c423dcf88952a13df86abd36c81746ff85ee502b --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/RegionOfInterest.msg @@ -0,0 +1,19 @@ +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify diff --git a/spider_control/msg/sensor_msgs/msg/RelativeHumidity.msg b/spider_control/msg/sensor_msgs/msg/RelativeHumidity.msg new file mode 100644 index 0000000000000000000000000000000000000000..202421f95dcc4019bab038fa937c0eebd7bc629b --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/RelativeHumidity.msg @@ -0,0 +1,12 @@ + # Single reading from a relative humidity sensor. Defines the ratio of partial + # pressure of water vapor to the saturated vapor pressure at a temperature. + + Header header # timestamp of the measurement + # frame_id is the location of the humidity sensor + + float64 relative_humidity # Expression of the relative humidity + # from 0.0 to 1.0. + # 0.0 is no partial pressure of water vapor + # 1.0 represents partial pressure of saturation + + float64 variance # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/Temperature.msg b/spider_control/msg/sensor_msgs/msg/Temperature.msg new file mode 100644 index 0000000000000000000000000000000000000000..7c6a4f761556269880b8a0d850b365cdfa66f009 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/Temperature.msg @@ -0,0 +1,8 @@ + # Single temperature reading. + + Header header # timestamp is the time the temperature was measured + # frame_id is the location of the temperature reading + + float64 temperature # Measurement of the Temperature in Degrees Celsius + + float64 variance # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/spider_control/msg/sensor_msgs/msg/TimeReference.msg b/spider_control/msg/sensor_msgs/msg/TimeReference.msg new file mode 100644 index 0000000000000000000000000000000000000000..1aeb3d3954388907bb0504f2970138ea424a88e6 --- /dev/null +++ b/spider_control/msg/sensor_msgs/msg/TimeReference.msg @@ -0,0 +1,7 @@ +# Measurement from an external time source not actively synchronized with the system clock. + +Header header # stamp is system time for which measurement was valid + # frame_id is not used + +time time_ref # corresponding time from this external source +string source # (optional) name of time source diff --git a/spider_control/msg/sensor_msgs/package.xml b/spider_control/msg/sensor_msgs/package.xml new file mode 100644 index 0000000000000000000000000000000000000000..81bdf5eb44ea1ffc42989d4bf7be7bc90d415396 --- /dev/null +++ b/spider_control/msg/sensor_msgs/package.xml @@ -0,0 +1,31 @@ + + sensor_msgs + 1.12.7 + + This package defines messages for commonly used sensors, including + cameras and scanning laser rangefinders. + + Tully Foote + BSD + + http://ros.org/wiki/sensor_msgs + + catkin + + geometry_msgs + message_generation + std_msgs + + geometry_msgs + message_runtime + std_msgs + + rosbag + rosunit + + + + + + + diff --git a/spider_control/msg/sensor_msgs/srv/SetCameraInfo.srv b/spider_control/msg/sensor_msgs/srv/SetCameraInfo.srv new file mode 100644 index 0000000000000000000000000000000000000000..9a8dcc074405a388450aa4bb78b072c319bd2c74 --- /dev/null +++ b/spider_control/msg/sensor_msgs/srv/SetCameraInfo.srv @@ -0,0 +1,12 @@ +# This service requests that a camera stores the given CameraInfo +# as that camera's calibration information. +# +# The width and height in the camera_info field should match what the +# camera is currently outputting on its camera_info topic, and the camera +# will assume that the region of the imager that is being referred to is +# the region that the camera is currently capturing. + +sensor_msgs/CameraInfo camera_info # The camera_info to store +--- +bool success # True if the call succeeded +string status_message # Used to give details about success diff --git a/spider_control/my_network.py b/spider_control/my_network.py new file mode 100755 index 0000000000000000000000000000000000000000..b7d812b9a0c4ad019de787941ad1447b9e34e42f --- /dev/null +++ b/spider_control/my_network.py @@ -0,0 +1,196 @@ +#!/usr/bin/python3 +import tensorflow as tf +import random +import numpy as np +from matplotlib import pylab +import pylab as plt +import math +import time +import leg_dynamics as ld + + + +class Architecture: + 'Common class defining the architecture of the neural network i.e. number of neurons in each layer and number of layers' + + def __init__(self, layers, neurons, number): + self.layers = layers + self.neurons = neurons + self.number = number#number of the model + #self.neurons_hidden_context = tf.compat.v1.placeholder(dtype = tf.float64, shape=[8, 1], name="hidden_context") + #self.is_filled = tf.compat.v1.placeholder(tf.bool) + self.neuron_hidden_context = None + self.weight_initer = tf.truncated_normal_initializer(mean=1.0, stddev=0.01) + self.weight_initer1 = tf.truncated_normal_initializer(mean=1.0, stddev=0.05) + self.weight_initer2 = tf.truncated_normal_initializer(mean=1.0, stddev=0.1) + self.weight_initer3 = tf.truncated_normal_initializer(mean=1.0, stddev=0.15) + self.bias_initer =tf.truncated_normal_initializer(mean=0.1, stddev=0.01) + self.bias_initer1 =tf.truncated_normal_initializer(mean=0.1, stddev=0.01) + self.bias_initer2 =tf.truncated_normal_initializer(mean=0.1, stddev=0.01) + self.bias_initer3 =tf.truncated_normal_initializer(mean=0.1, stddev=0.01) + # get neuron value method helps us to write the joint angles to the individual neurons which we can later use for learning + def reward_method(self, j_angles): + mask = tf.compat.v1.constant([0.12, 0.33, 0.5]) + mask = tf.compat.v1.tile(mask, [2]) + mask_1 = tf.compat.v1.constant([0.12, 0.33, 0.5]) + mask_1 = tf.compat.v1.tile(mask_1, [8]) + mask_1 = tf.compat.v1.reshape(mask_1, shape=[8, 3]) + j_angles_0 = tf.compat.v1.reshape(j_angles, shape=[4, 6]) + j_angles_1 = tf.compat.v1.reshape(j_angles, shape=[8, 3]) + com_1 = tf.compat.v1.multiply(mask, j_angles_0[0, :]) + com_2 = tf.compat.v1.multiply(mask, j_angles_0[1, :]) + com_3 = tf.compat.v1.multiply(mask, j_angles_0[2, :]) + com_4 = tf.compat.v1.multiply(mask, j_angles_0[3, :]) + x_com_1 = tf.compat.v1.math.cos(com_1) + x_com_2 = tf.compat.v1.math.cos(com_2) + x_com_3 = tf.compat.v1.math.cos(com_3) + x_com_4 = tf.compat.v1.math.cos(com_4) + y_com_1 = tf.compat.v1.math.sin(com_1) + y_com_2 = tf.compat.v1.math.sin(com_2) + y_com_3 = tf.compat.v1.math.sin(com_3) + y_com_4 = tf.compat.v1.math.sin(com_4) + x_com = tf.add(tf.add(tf.add(x_com_1, x_com_2), x_com_3), x_com_4) + y_com = tf.add(tf.add(tf.add(y_com_1, y_com_2), y_com_3), y_com_4) + m_com = tf.compat.v1.multiply(mask_1, j_angles_1) + m_com_x = tf.compat.v1.math.cos(m_com) + m_com_x = tf.compat.v1.math.reduce_sum(m_com_x) + m_com_y = tf.compat.v1.math.sin(m_com) + m_com_y = tf.compat.v1.math.reduce_sum(m_com_y) + x_mid = 0.5*(tf.add(x_com[0:2], x_com[3:5])) + y_mid = 0.5*(tf.add(y_com[0:2], y_com[3:5])) + x_mid = tf.compat.v1.math.reduce_sum(x_mid) + y_mid = tf.compat.v1.math.reduce_sum(y_mid) + m = 0.017*(tf.compat.v1.math.divide(tf.compat.v1.math.subtract(m_com_y, y_mid),tf.compat.v1.math.subtract(m_com_x, x_mid))) + return m + def NN_learningPunishment(self, LearningRate, punishment): + #a method to minimize the rewards and alot the weights based on that + optimizer = tf.train.GradientDescentOptimizer(LearningRate).minimize(punishment) + with tf.Session as sess: + sess.run(optimizer) + return + def NN_learningReward(self, LearningRate, reward): + #a method to maximize reward and alot the weights based on that + reward = -1*reward + optimizer = tf.train.GradientDescentOptimizer(LearningRate).minimize(reward) + init_m = tf.compat.v1.global_variables_initializer() + with tf.Session as session: + session.run(init_m) + session.run(optimizer) + def output_function(self, a = []): + b = tf.nn.softmax(a, name='sigmoid') + out = b*a + return out + def get_var_list(self): + ls = tf.trainable_variables() + iii = tf.global_variables_initializer() + with tf.Session() as sessio: + sessio.run(iii) + l = sessio.run(ls) + return l, ls + def nn_run(self, joint_angles): + m_dict = {} + #function that directly runs the neural network and returns the prediction + joint_angles = tf.compat.v1.convert_to_tensor(joint_angles, dtype=tf.float32) + joint_angles = tf.compat.v1.reshape(joint_angles, shape=[24, 1]) + sessi = tf.InteractiveSession() + with tf.compat.v1.variable_scope("weight_in_main", reuse=tf.compat.v1.AUTO_REUSE): + weight_i_m = tf.compat.v1.get_variable("weight_input_main", dtype=tf.float32, shape=[self.neurons, 1], initializer=self.weight_initer) + init_i_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_i_m) + with tf.compat.v1.variable_scope("weight_hid_main", reuse=tf.compat.v1.AUTO_REUSE): + weights_h_m = tf.compat.v1.get_variable("weight_hidden_main", dtype=tf.float32, shape=[int(self.neurons/3), int(self.layers)], initializer=self.weight_initer1) + init_h_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_h_m) + with tf.compat.v1.variable_scope("weight_hid_cont_main", reuse=tf.compat.v1.AUTO_REUSE): + weights_h_c_m = tf.compat.v1.get_variable("weight_hid_cont_main", dtype=tf.float32, shape=[int(self.neurons/3), 1], initializer=self.weight_initer2) + init_h_c_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_h_c_m) + with tf.compat.v1.variable_scope("weight_out_main", reuse=tf.compat.v1.AUTO_REUSE): + weights_o_m = tf.compat.v1.get_variable("weight_input_main", dtype=tf.float32, shape=[int(self.neurons), 1], initializer=self.weight_initer3) + init_o_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_o_m) + with tf.compat.v1.variable_scope("bias_in_main", reuse=tf.compat.v1.AUTO_REUSE): + bias_i_m = tf.compat.v1.get_variable("bias_input_main", dtype=tf.float32, shape=[self.neurons, 1], initializer=self.bias_initer) + init_i_b_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_i_b_m) + with tf.compat.v1.variable_scope("bias_hid_main", reuse=tf.compat.v1.AUTO_REUSE): + bias_h_m = tf.compat.v1.get_variable("bias_hidden_main", dtype=tf.float32, shape=[int(self.neurons/3), 1], initializer=self.bias_initer1) + init_h_b_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_h_b_m) + with tf.compat.v1.variable_scope("bias_hid_cont_main", reuse=tf.compat.v1.AUTO_REUSE): + bias_h_c_m = tf.compat.v1.get_variable("bias_hidden_cont_main", dtype=tf.float32, shape=[int(self.neurons/3), 1], initializer=self.bias_initer2) + init_h_c_b_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_h_c_b_m) + with tf.compat.v1.variable_scope("bias_out_main", reuse=tf.compat.v1.AUTO_REUSE): + bias_o_m = tf.compat.v1.get_variable("bias_out_main", dtype=tf.float32, shape=[int(self.neurons), 1], initializer=self.bias_initer3) + init_o_b_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_o_b_m) + uninitialized_variables_main = [] + print("printing the names of all variables") + print(tf.all_variables()) + for var in tf.all_variables(): + try: + sessi.run(var) + except tf.errors.FailedPreconditionError: + uninitialized_variables_main.append(var) + + init_m = tf.variables_initializer(uninitialized_variables_main) + sessi.run(init_m) + input_layer_activation = tf.add(tf.multiply(joint_angles, weight_i_m), bias_i_m) + input_layer_output = tf.compat.v1.nn.leaky_relu(input_layer_activation, alpha=0.05) + print("printing joint angles fr main network") + print(tf.compat.v1.shape(input_layer_output)) + input_layer_output = tf.compat.v1.reshape(input_layer_output, shape=[8, 3]) + if(self.neuron_hidden_context != None): + n_h_c = tf.compat.v1.convert_to_tensor(self.neuron_hidden_context, dtype=tf.float32) + input_layer_out = tf.compat.v1.concat([input_layer_output, n_h_c], 1) + hidden_layer_activation_multiply = tf.compat.v1.multiply(input_layer_out, weights_h_m) + hidden_layer_activation_input = tf.compat.v1.add(hidden_layer_activation_multiply[:,0], hidden_layer_activation_multiply[:, 1]) + hidden_layer_activation_input = tf.compat.v1.add(hidden_layer_activation_input, hidden_layer_activation_multiply[:, 2]) + hidden_layer_activation_input = tf.compat.v1.add(hidden_layer_activation_input, hidden_layer_activation_multiply[:,3]) + hidden_layer_activation_input = tf.compat.v1.reshape(hidden_layer_activation_input, [8, 1]) + hidden_layer_activation = tf.compat.v1.add(hidden_layer_activation_input, bias_h_m) + elif(self.neuron_hidden_context == None): + hidden_layer_activation_multiply = tf.compat.v1.multiply(input_layer_output, weights_h_m[:,0:3]) + hidden_layer_activation_input = tf.compat.v1.add(hidden_layer_activation_multiply[:,0], hidden_layer_activation_multiply[:, 1]) + hidden_layer_activation_input = tf.compat.v1.add(hidden_layer_activation_input, hidden_layer_activation_multiply[:, 2]) + hidden_layer_activation_input = tf.compat.v1.reshape(hidden_layer_activation_input, [8, 1]) + hidden_layer_activation = tf.compat.v1.add(hidden_layer_activation_input, bias_h_m) + hidden_layer_output = tf.compat.v1.nn.leaky_relu(hidden_layer_activation, alpha=0.05) + print("printing hidden_layer_out") + print(sessi.run(hidden_layer_output)) + neurons_hidden_context = tf.compat.v1.add(tf.compat.v1.multiply(hidden_layer_output, weights_h_c_m), bias_h_c_m) + print("printing hidden_layer_out") + print(sessi.run(neurons_hidden_context)) + self.neuron_hidden_context = tf.compat.v1.nn.leaky_relu(neurons_hidden_context, alpha=0.05) + output_layer_mask = tf.compat.v1.constant([0.25, 0.25, 0.5]) + output_layer_mask = tf.compat.v1.tile(output_layer_mask, [8]) + output_layer_mask = tf.compat.v1.reshape(output_layer_mask, [8, 3]) + output_layer_mask = tf.compat.v1.cast(output_layer_mask, dtype=tf.float32) + output_layer_input = tf.compat.v1.multiply(hidden_layer_output, output_layer_mask) + output_layer_input = tf.compat.v1.reshape(output_layer_input, [24, 1]) + output_layer_activation = tf.compat.v1.add(tf.compat.v1.multiply(output_layer_input, weights_o_m), bias_o_m) + output_layerout = tf.compat.v1.nn.leaky_relu(output_layer_activation, alpha=0.05) + variables_list_m, variables_m = self.get_var_list() + for var, val in zip(variables_m, variables_list_m): + #print("var: {}, value: {}".format(var.name, val)) + m_dict[var.name] = val + reward = self.reward_method(output_layerout) + learningrate = 0.01 + reward = -1*reward + optimizer = tf.train.GradientDescentOptimizer(learningrate).minimize(reward) + init_m = tf.compat.v1.global_variables_initializer() + sessi.run(init_m) + sessi.run(optimizer) + out = sessi.run(output_layerout) + print("printing the shape of input of output layer") + print(out) + out = np.nan_to_num(out, posinf=1.35) + return out, m_dict + def nn_learn(self, rew): + Learningrate = 0.1 + self.NN_learningReward(Learningrate, rew) + + + + diff --git a/spider_control/package.xml b/spider_control/package.xml index c40b86fd551e2d622b27d76626337a80237ea814..788f681bf509ab13314b9700c1333ee4dc51c80d 100644 --- a/spider_control/package.xml +++ b/spider_control/package.xml @@ -52,13 +52,22 @@ catkin roscpp rospy + message_generation + geometry_msgs + sensor_msgs controller_manager joint_state_controller robot_state_publisher - + geometry_msgs + sensor_msgs rqt_gui effort_controllers - + position_controllers + message_runtime + roscpp + rospy + stdmsgs + message_generation diff --git a/spider_description/urdf/spider.gazebo b/spider_description/urdf/spider.gazebo index 0045a405443f381b789e20303613a5595fa814e4..ac54a8ed8f65139474fbec3b9c04f85dafd0267c 100644 --- a/spider_description/urdf/spider.gazebo +++ b/spider_description/urdf/spider.gazebo @@ -4,7 +4,7 @@ - /spider + spider gazebo_ros_control/DefaultRobotHWSim true @@ -13,7 +13,7 @@ spider - joint_1_1,joint_1_2,joint_1_3,joint_2_1,joint_2_2,joint_2_3,joint_3_1,joint_3_2,joint_3_3,joint_4_1,joint_4_2,joint_4_3,joint_5_1,joint_5_2,joint_5_3,joint_6_1,joint_6_2,joint_6_3,joint_7_1,joint_7_2,joint_7_3,joint_8_1,joint_8_2,joint_8_3 + joint_1_1,joint_1_2,joint_1_3,joint_2_1,joint_2_2,joint_2_3,joint_3_1,joint_3_2,joint_3_3,joint_4_1,joint_4_2,joint_4_3,joint_5_1,joint_5_2,joint_5_3,joint_6_1,joint_6_2,joint_6_3,joint_7_1,joint_7_2,joint_7_3,joint_8_1,joint_8_2,joint_8_3 100 true @@ -22,10 +22,12 @@ Gazebo/Orange + true + true 0.2 0.2 Gazebo/Black @@ -33,6 +35,7 @@ + true 0.2 0.2 Gazebo/Black @@ -40,6 +43,7 @@ + true 0.2 0.2 Gazebo/Black @@ -47,6 +51,7 @@ + true 0.2 0.2 Gazebo/Black @@ -54,6 +59,7 @@ + true 0.2 0.2 Gazebo/Black @@ -61,6 +67,7 @@ + true 0.2 0.2 Gazebo/Black @@ -68,6 +75,7 @@ + true 0.2 0.2 Gazebo/Black @@ -75,6 +83,7 @@ + true 0.2 0.2 Gazebo/Black @@ -82,6 +91,7 @@ + true 0.2 0.2 Gazebo/Black @@ -89,6 +99,7 @@ + true 0.2 0.2 Gazebo/Black @@ -96,6 +107,7 @@ + true 0.2 0.2 Gazebo/Black @@ -103,6 +115,7 @@ + true 0.2 0.2 Gazebo/Black @@ -110,6 +123,7 @@ + true 0.2 0.2 Gazebo/Black @@ -117,6 +131,7 @@ + true 0.2 0.2 Gazebo/Black @@ -131,6 +146,7 @@ + true 0.2 0.2 Gazebo/Black @@ -138,6 +154,7 @@ + true 0.2 0.2 Gazebo/Black @@ -145,6 +162,7 @@ + true 0.2 0.2 Gazebo/Black @@ -152,6 +170,7 @@ + true 0.2 0.2 Gazebo/Black @@ -159,6 +178,7 @@ + true 0.2 0.2 Gazebo/Black @@ -166,6 +186,7 @@ + true 0.2 0.2 Gazebo/Black @@ -173,6 +194,7 @@ + true 0.2 0.2 Gazebo/Black @@ -180,6 +202,7 @@ + true 0.2 0.2 Gazebo/Black @@ -187,6 +210,7 @@ + true 0.2 0.2 Gazebo/Black @@ -194,6 +218,7 @@ + true 0.2 0.2 Gazebo/Black @@ -201,9 +226,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -222,9 +247,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -243,9 +268,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -264,9 +289,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -285,9 +310,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -306,9 +331,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -327,9 +352,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 @@ -348,9 +373,9 @@ - + 0.0 0.0 0.0 0.0 0 0 - false + true 10 diff --git a/spider_description/urdf/spider.xacro b/spider_description/urdf/spider.xacro index 25e37e803d2e387e1125a43af78227a45b518ef3..b4ca24465284c33f3f5042f938d70f7b638738de 100644 --- a/spider_description/urdf/spider.xacro +++ b/spider_description/urdf/spider.xacro @@ -4,29 +4,63 @@ - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + + + + 0x001 + + @@ -37,38 +71,40 @@ - - - - - - + + + + + + - - + + - - + + - + + + + 0x010 + + - + @@ -76,23 +112,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -102,6 +138,11 @@ + + + 0x011 + + @@ -116,9 +157,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -128,8 +169,8 @@ - - + + @@ -139,6 +180,11 @@ + + + 0x100 + + @@ -153,33 +199,38 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -187,23 +238,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -213,6 +264,11 @@ + + + 0x011 + + @@ -227,9 +283,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -239,8 +295,8 @@ - - + + @@ -250,6 +306,11 @@ + + + 0x100 + + @@ -264,33 +325,38 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -298,23 +364,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -323,6 +389,11 @@ + + + 0x011 + + @@ -337,9 +408,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -349,16 +420,21 @@ - - + + - + + + + 0x100 + + @@ -373,9 +449,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -383,23 +459,28 @@ - - + + - - + + - + + + + 0x010 + + - + @@ -407,31 +488,36 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + - + + + + 0x011 + + @@ -446,9 +532,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -458,8 +544,8 @@ - - + + @@ -468,6 +554,11 @@ + + + 0x100 + + @@ -482,32 +573,37 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -515,23 +611,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -540,6 +636,11 @@ + + + 0x011 + + @@ -554,9 +655,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -566,8 +667,8 @@ - - + + @@ -576,6 +677,11 @@ + + + 0x100 + + @@ -590,32 +696,37 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -623,23 +734,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -648,6 +759,11 @@ + + + 0x011 + + @@ -662,9 +778,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -674,8 +790,8 @@ - - + + @@ -684,6 +800,11 @@ + + + 0x100 + + @@ -698,32 +819,37 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -731,23 +857,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -756,6 +882,11 @@ + + + 0x011 + + @@ -770,9 +901,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -782,8 +913,8 @@ - - + + @@ -792,6 +923,11 @@ + + + 0x100 + + @@ -806,32 +942,37 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - - + + - - + + - + + + + 0x010 + + - + @@ -839,23 +980,23 @@ - + + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> - + - - + + @@ -864,6 +1005,11 @@ + + + 0x011 + + @@ -878,9 +1024,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_1_2)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -890,8 +1036,8 @@ - - + + @@ -900,6 +1046,11 @@ + + + 0x100 + + @@ -914,9 +1065,9 @@ + ixx="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" ixy="0.0" ixz="0.0" + iyy="${(mass_link*(3*(radius_link)**2+(height_link_3)**2))/2}" iyz="0.0" + izz="${(mass_chassis*(radius_link)**2)/2}"/> @@ -945,7 +1096,7 @@ - + @@ -974,7 +1125,7 @@ - + @@ -1003,7 +1154,7 @@ - + @@ -1032,7 +1183,7 @@ - + @@ -1061,7 +1212,7 @@ - + @@ -1090,7 +1241,7 @@ - + @@ -1119,7 +1270,7 @@ - + @@ -1148,7 +1299,7 @@ - + @@ -1158,9 +1309,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface + 1 @@ -1168,10 +1320,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1179,10 +1331,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1190,10 +1342,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1201,10 +1353,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1212,10 +1364,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1223,10 +1375,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1234,10 +1386,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1245,10 +1397,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1256,10 +1408,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1267,10 +1419,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1278,10 +1430,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1289,10 +1441,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1300,10 +1452,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1311,21 +1463,21 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - - 1 + + 1 transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1333,10 +1485,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1344,10 +1496,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1355,10 +1507,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1366,10 +1518,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1377,10 +1529,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1388,10 +1540,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1399,10 +1551,10 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - + 1 @@ -1410,11 +1562,11 @@ transmission_interface/SimpleTransmission - EffortJointInterface + PositionJointInterface - - 1 + + 1 diff --git a/spider_gazebo/launch/spider_world.launch b/spider_gazebo/launch/spider_world.launch old mode 100644 new mode 100755 index ecb97d73d478a7a727ee85092eb21ab7f4d2712c..0780f5a0f1a825e7be648353d8ca26c718c966e0 --- a/spider_gazebo/launch/spider_world.launch +++ b/spider_gazebo/launch/spider_world.launch @@ -7,6 +7,7 @@ + @@ -15,15 +16,17 @@ + + + args="-urdf -param robot_description -model spider" /> diff --git a/spider_gazebo/package.xml b/spider_gazebo/package.xml index 0bdde01cef37e81a8221feb2f9d0839bcb0c955a..8440dda48f96588a20c3a992d4f5e3009d9c9b49 100644 --- a/spider_gazebo/package.xml +++ b/spider_gazebo/package.xml @@ -1,7 +1,7 @@ - + spider_gazebo - 0.0.0 + 2.5.19 The spider_gazebo package @@ -50,12 +50,12 @@ catkin - gazebo_plugins - gazebo_ros - gazebo_ros_control - spider_control - spider_description - xacro + gazebo_plugins + gazebo_ros + gazebo_ros_control + spider_control + spider_description + xacro diff --git a/spider_gazebo/worlds/Antactica.tif b/spider_gazebo/worlds/Antactica.tif deleted file mode 100644 index d9f4b7efbdd572fad9e3fd2ae629832c81ff3ef6..0000000000000000000000000000000000000000 Binary files a/spider_gazebo/worlds/Antactica.tif and /dev/null differ diff --git a/spider_gazebo/worlds/Stone_Brushed_Khaki_.png b/spider_gazebo/worlds/Stone_Brushed_Khaki_.png new file mode 100644 index 0000000000000000000000000000000000000000..ad44d9013e333b4d49468eae26165d27b0c6c303 Binary files /dev/null and b/spider_gazebo/worlds/Stone_Brushed_Khaki_.png differ diff --git a/spider_gazebo/worlds/__Wood_Bamboo_Medium_1.png b/spider_gazebo/worlds/__Wood_Bamboo_Medium_1.png new file mode 100644 index 0000000000000000000000000000000000000000..8f055c50520997836d7558b19870bfb5528aaea5 Binary files /dev/null and b/spider_gazebo/worlds/__Wood_Bamboo_Medium_1.png differ diff --git a/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/AS16-110-18026HR-512x512.jpg b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/AS16-110-18026HR-512x512.jpg new file mode 100644 index 0000000000000000000000000000000000000000..d1fe7b4ed9c88dadfa5a25c29943401fc7640bf0 Binary files /dev/null and b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/AS16-110-18026HR-512x512.jpg differ diff --git a/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png new file mode 100644 index 0000000000000000000000000000000000000000..7fe4bd95821d05161d62e21559851bffa638bdb1 Binary files /dev/null and b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png differ diff --git a/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model-1_4.sdf b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model-1_4.sdf new file mode 100644 index 0000000000000000000000000000000000000000..4c0ee67b5a7fd6af277558cc6d983a148b02f477 --- /dev/null +++ b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model-1_4.sdf @@ -0,0 +1,48 @@ + + + + true + + + + + + 0.2 + + + + + 1 + 100000 + 1 + 0.000001 + 0.02 + + + + + + model://apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png + 514 514 49 + 0 0 -45 + + + + + + + + file://media/materials/textures/AS16-110-18026HR-512x512.jpg + + file://media/materials/textures/flat_normal.png + 2 + + model://apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png + 514 514 49 + 0 0 -45 + + + + + + diff --git a/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.config b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.config new file mode 100644 index 0000000000000000000000000000000000000000..253b84547867445c0f7d99f6939f0a9e85701736 --- /dev/null +++ b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.config @@ -0,0 +1,17 @@ + + + + Apollo15 Landing Site Heightmap 1000x1000 meters + 1.0 + model-1_4.sdf + + + Kei Okada + kei.okada@gmail.com + + + + Terrain generated from http://wms.lroc.asu.edu/lroc/view_rdr_product/NAC_DTM_APOLLO15 + + + diff --git a/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.sdf b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.sdf new file mode 100644 index 0000000000000000000000000000000000000000..4c0ee67b5a7fd6af277558cc6d983a148b02f477 --- /dev/null +++ b/spider_gazebo/worlds/apollo15_landing_site_1000x1000/model.sdf @@ -0,0 +1,48 @@ + + + + true + + + + + + 0.2 + + + + + 1 + 100000 + 1 + 0.000001 + 0.02 + + + + + + model://apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png + 514 514 49 + 0 0 -45 + + + + + + + + file://media/materials/textures/AS16-110-18026HR-512x512.jpg + + file://media/materials/textures/flat_normal.png + 2 + + model://apollo15_landing_site_1000x1000/materials/textures/NAC_DTM_APOLLO15_E261N0036_257x257+7472+2152.png + 514 514 49 + 0 0 -45 + + + + + + diff --git a/spider_gazebo/worlds/cinderblock2/meshes/cinder_block_wide.dae b/spider_gazebo/worlds/cinderblock2/meshes/cinder_block_wide.dae new file mode 100755 index 0000000000000000000000000000000000000000..0f31f3c95ed93e98809a89d7df632260196b0d9f --- /dev/null +++ b/spider_gazebo/worlds/cinderblock2/meshes/cinder_block_wide.dae @@ -0,0 +1,253 @@ + + + + + Blender User + Blender 2.68.0 r58536 + + 2013-08-29T09:40:51 + 2013-08-29T09:40:51 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 45 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.512 0.512 0.512 1 + + + 0.125 0.125 0.125 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.512 0.512 0.512 1 + + + 0.125 0.125 0.125 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + -7.62507 7.62507 5.625 7.625068 7.62507 -2.38419e-7 7.625068 7.62507 5.625 -7.62507 7.62507 -2.38419e-7 7.625068 6.812334 0.9999998 7.625067 -6.812468 0.9999998 7.625068 6.812334 4.625 7.625067 0.5001326 4.625 7.625067 -0.499867 4.625 7.625067 -6.812468 4.625 7.625067 -7.62507 -2.38419e-7 7.625067 -7.62507 5.625 7.625067 0.5001326 0.9999998 7.625067 -0.499867 0.9999998 -7.62507 -7.62507 5.625 -7.62507 -7.62507 -2.38419e-7 -7.624935 -6.812467 0.9999998 -7.624935 -6.812467 4.625 -7.624935 -0.4998655 4.625 -7.624934 6.812335 4.625 -7.624934 6.812335 0.9999998 -7.624935 -0.4998655 0.9999998 -7.624935 0.500134 0.9999998 -7.624935 0.500134 4.625 + + + + + + + + + + 1 0 0 1 0 9.53674e-7 1 0 9.53674e-7 0 -1 0 0 0 -1 0 0 1 0 1 0 0 0 -1 0 1 0 0 -1 0 1 0 0 1 0 -9.53674e-7 0 0 1 -1 0 1.34945e-4 -1 0 1.34945e-4 -1 0 -1.34945e-4 1 0 0 1 0 0 1 -1.51084e-7 -1.22792e-7 -1 1.51084e-7 1.36021e-4 -1 1.51084e-7 -1.33717e-4 -1 0 0 -1 0 0 0 -1 0 0 0 -1 0 0 1 0 1 0 0 0 -1 0 1 0 0 -1 0 0 0 1 0 1 0 0 1 0 -1 1.66065e-4 0 -1 1.66065e-4 0 1 0 0 1 0 0 1 0 -9.53674e-7 1 0 0 1 0 0 1 -1.51084e-7 1.22792e-7 0 0 1 0 0 1 -1 0 -1.35899e-4 -1 -1.67211e-4 0 -1 -1.67211e-4 0 -1 0 -1.34945e-4 -1 0 1.34945e-4 0 0 -1 0 0 -1 0 -1 0 0 -1 0 + + + + + + + + + + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -87.91291 -2.89646 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 87.75421 -7.52561 0 0 -89.1988 -3.81721 0 0 0 0 0 0 0 0 0 0 91.2149 -7.52561 0 0 0 0 0 0 0 0 0 0 -91.46891 -4.07121 -87.91291 -3.81721 0 0 0 0 0 0 0 0 0 0 0 0 0 0 87.91291 -7.36686 0 0 0 0 0 0 87.50019 -8.54161 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -91.46891 -4.07121 0 0 0 0 0 0 91.46891 -7.11286 91.0562 -8.287611 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -91.05622 -3.81721 0 0 0 0 0 0 0 0 87.75421 -7.52561 0 0 0 0 0 0 87.91291 -8.287611 0 0 0 0 0 0 0 0 0 0 -91.21492 -3.05521 0 0 0 0 0 0 0 0 -91.46891 -4.07121 -91.46891 -7.94471 -90.04016 -4.07121 -90.04016 -7.94471 -90.04016 -4.07121 -91.46891 -7.94471 87.75421 -7.52561 87.50019 -8.54161 87.5002 -7.11286 87.75421 -7.52561 87.75421 -8.128863 87.50019 -8.54161 -87.5002 -4.07121 -91.46891 -4.07121 -87.91291 -3.81721 -87.91291 -2.89646 -91.46891 -2.64246 -87.5002 -2.64246 -89.1988 -3.81721 -87.91291 -3.81721 -91.46891 -4.07121 -91.21492 -3.05521 -91.21492 -3.65846 -91.46891 -4.07121 -91.21492 -3.05521 -91.46891 -4.07121 -91.46891 -2.64246 -91.05622 -3.81721 -89.7703 -3.81721 -91.46891 -4.07121 -87.5002 -7.94471 -91.46891 -7.94471 -91.46891 -4.07121 -91.46891 -4.07121 -87.5002 -4.07121 -87.5002 -7.94471 91.46891 -8.54161 87.50019 -8.54161 91.0562 -8.287611 91.46891 -8.54161 91.2149 -8.128863 91.2149 -7.52561 91.46891 -7.11286 91.46891 -8.54161 91.2149 -7.52561 87.91291 -8.287611 89.1988 -8.287611 87.50019 -8.54161 87.5002 -7.11286 91.46891 -7.11286 87.91291 -7.36686 85.51585 -12.92311 89.48455 -12.92311 85.51585 -9.049612 89.48455 -9.049612 85.51585 -9.049612 89.48455 -12.92311 -7.11286 -4.07121 -7.11286 -7.94471 -8.54161 -7.94471 -8.54161 -7.94471 -8.54161 -4.07121 -7.11286 -4.07121 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

10 0 0 5 0 1 11 0 2 1 1 3 12 1 4 13 1 5 1 2 6 13 2 7 5 2 8 21 3 9 13 3 10 18 3 11 23 4 12 19 4 13 7 4 14 5 5 15 13 5 16 16 5 17 5 6 18 16 6 19 9 6 20 8 7 21 9 7 22 18 7 23 12 8 24 22 8 25 7 8 26 19 9 27 20 9 28 6 9 29 13 10 30 7 10 31 8 10 32 7 11 33 2 11 34 8 11 35 4 12 36 20 12 37 12 12 38 21 13 39 22 13 40 3 13 41 3 14 42 16 14 43 21 14 44 23 15 45 18 15 46 14 15 47 13 16 48 12 16 49 7 16 50 11 17 51 5 17 52 9 17 53 12 18 54 1 18 55 4 18 56 22 19 57 20 19 58 3 19 59 14 20 60 19 20 61 23 20 62 22 21 63 21 21 64 18 21 65 22 22 66 18 22 67 23 22 68 13 23 69 8 23 70 18 23 71 19 24 72 6 24 73 7 24 74 13 25 75 21 25 76 16 25 77 16 26 78 17 26 79 9 26 80 9 27 81 17 27 82 18 27 83 22 28 84 23 28 85 7 28 86 20 29 87 4 29 88 6 29 89 20 30 90 22 30 91 12 30 92

+
+ + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 31 93 2 31 94 1 31 95 1 32 96 3 32 97 0 32 98 14 33 99 16 33 100 15 33 101 17 34 102 16 34 103 14 34 104 2 35 105 11 35 106 9 35 107 1 36 108 5 36 109 10 36 110 9 37 111 8 37 112 2 37 113 6 38 114 4 38 115 2 38 116 2 39 117 4 39 118 1 39 119 7 40 120 6 40 121 2 40 122 0 41 123 14 41 124 2 41 125 11 42 126 2 42 127 14 42 128 14 43 129 0 43 130 19 43 131 19 44 132 0 44 133 20 44 134 0 45 135 3 45 136 20 45 137 18 46 138 17 46 139 14 46 140 3 47 141 15 47 142 16 47 143 1 48 144 10 48 145 15 48 146 15 49 147 3 49 148 1 49 149 15 50 150 10 50 151 14 50 152 11 51 153 14 51 154 10 51 155

+
+
+ 1 +
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.0254 0 0 0 0 0.0254 0 0 0 0 0.0254 0 0 0 0 1 + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/spider_gazebo/worlds/cinderblock2/model.config b/spider_gazebo/worlds/cinderblock2/model.config new file mode 100644 index 0000000000000000000000000000000000000000..d060969bce201e30d5184b266aa0ab51b429d4b2 --- /dev/null +++ b/spider_gazebo/worlds/cinderblock2/model.config @@ -0,0 +1,17 @@ + + + + Cinder block wide + 1.0 + model.sdf + + + Nate Koenig + natekoenig@gmail.com + + + + A model of a wide cinder block. + + + diff --git a/spider_gazebo/worlds/cinderblock2/model.sdf b/spider_gazebo/worlds/cinderblock2/model.sdf new file mode 100644 index 0000000000000000000000000000000000000000..bd3aa866e33958703a4d7a68ea94db548c9f4310 --- /dev/null +++ b/spider_gazebo/worlds/cinderblock2/model.sdf @@ -0,0 +1,137 @@ + + + + + + 0 0 0.0714375 0 0 0 + 5 + + + 0.06814656666666667 + 0.0000 + 0.06814656666666667 + 0.0000 + 0.0000 + 0.1248075 + + + + + + model://cinderblock2/meshes/cinder_block_wide.dae + + + + + 0 0 0.130175 0 0 0 + + + 0.387353556 0.387353556 0.0254 + + + + + + 0.1 + 0.001 + + + + + 1.0 + 1.0 + + + + + + 0 0 0.0127 0 0 0 + + + 0.387353556 0.387353556 0.0254 + + + + + + 0.1 + 0.001 + + + + + 1.0 + 1.0 + + + + + + 0 -0.183355107 0.0714375 0 0 0 + + + 0.387353556 0.020643342 0.092075 + + + + + + 0.1 + 0.001 + + + + + 1.0 + 1.0 + + + + + + 0 0.183355107 0.0714375 0 0 0 + + + 0.387353556 0.020643342 0.092075 + + + + + + 0.1 + 0.001 + + + + + 1.0 + 1.0 + + + + + + 0 0 0.0714375 0 0 0 + + + 0.387353556 0.0254 0.092075 + + + + + + 0.1 + 0.001 + + + + + 1.0 + 1.0 + + + + + + + diff --git a/spider_gazebo/worlds/dem.aux.xml b/spider_gazebo/worlds/dem.aux.xml new file mode 100644 index 0000000000000000000000000000000000000000..c6b9d3e246886466bd144526bf81e4655234685a --- /dev/null +++ b/spider_gazebo/worlds/dem.aux.xml @@ -0,0 +1,9 @@ + + + Point + + + 0.00000000000000E+00 + Gray + + diff --git a/spider_gazebo/worlds/ramp2/materials/textures/plywood256x256.png b/spider_gazebo/worlds/ramp2/materials/textures/plywood256x256.png new file mode 100644 index 0000000000000000000000000000000000000000..6f7798071e5e7abb62b1202e975bbd702b37b1c5 Binary files /dev/null and b/spider_gazebo/worlds/ramp2/materials/textures/plywood256x256.png differ diff --git a/spider_gazebo/worlds/ramp2/meshes/nist_simple_ramp_120.dae b/spider_gazebo/worlds/ramp2/meshes/nist_simple_ramp_120.dae new file mode 100644 index 0000000000000000000000000000000000000000..8ecdad5808a49b9ff2d9601c3f6300ed4e3d5249 --- /dev/null +++ b/spider_gazebo/worlds/ramp2/meshes/nist_simple_ramp_120.dae @@ -0,0 +1,136 @@ + + + + + Stefan Kohlbrecher + Blender 2.61.4 r44005 + + 2012-02-12T17:33:59 + 2012-02-12T17:33:59 + + Z_UP + + + + ../materials/textures/plywood256x256.png + + + + + + + + plywood256x256_jpg + + + + + plywood256x256_jpg-surface + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + 0.59 0.59 -1.19209e-7 0.5899999 -0.59 1.18 -0.59 -0.5899999 1.18 -0.5899999 0.5900003 -1.19209e-7 0.5900003 0.5899997 0.01999986 0.5899997 -0.5900004 1.2 -0.5900002 -0.5899998 1.2 -0.59 0.59 0.01999986 + + + + + + + + + + 2.52562e-7 1 1.49012e-5 2.0205e-7 1 1.19209e-5 -1 -5.85941e-6 -5.96043e-6 -1 -5.85951e-6 -5.96054e-6 0 -1 -2.08616e-5 -5.05124e-7 -1 5.96047e-6 1 -1.20221e-5 -1.19211e-5 1 1.14161e-5 1.19212e-5 1.78588e-7 0.7071069 0.7071067 3.57177e-7 0.7071068 0.7071068 0 -0.7071068 -0.7071068 -1.21077e-7 -0.7071068 -0.7071068 + + + + + + + + + + 0.4897065 0.9505779 0.4897378 0.9608398 -0.3665395 0.9532045 0.4897378 0.9608398 -0.366508 0.9634668 -0.3665395 0.9532045 1.359992 0.9505833 1.34973 0.9608454 1.34973 -0.2500746 1.359992 0.9505833 1.34973 -0.2500746 1.359992 -0.2603368 0.4897691 -0.2474479 0.4897378 -0.25771 1.346015 -0.2500749 0.4897378 -0.25771 1.345984 -0.2603368 1.346015 -0.2500749 1.359992 -0.2603368 1.370254 -0.2500746 1.359992 0.9505832 1.370254 -0.2500746 1.370254 0.9608455 1.359992 0.9505832 0.4897065 0.9505779 -0.3665395 0.9532045 -0.3702542 -0.2577099 0.4897065 0.9505779 -0.3702542 -0.2577099 0.4859914 -0.2603368 0.4934841 0.9634665 0.4897691 -0.2474479 1.346015 -0.2500749 0.4934841 0.9634665 1.346015 -0.2500749 1.34973 0.9608399 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 +

4 0 0 0 0 1 7 0 2 0 1 3 3 1 4 7 1 5 2 2 6 6 2 7 7 2 8 2 3 9 7 3 10 3 3 11 1 4 12 5 4 13 2 4 14 5 5 15 6 5 16 2 5 17 0 6 18 4 6 19 1 6 20 4 7 21 5 7 22 1 7 23 4 8 24 7 8 25 6 8 26 4 9 27 6 9 28 5 9 29 0 10 30 1 10 31 2 10 32 0 11 33 2 11 34 3 11 35

+
+
+ 1 +
+
+ + + + 2.98023e-8 0 0 + 0 0 1 -180 + 0 1 0 0 + 1 0 0 0 + 1 1 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/spider_gazebo/worlds/ramp2/model-1_2.sdf b/spider_gazebo/worlds/ramp2/model-1_2.sdf new file mode 100644 index 0000000000000000000000000000000000000000..fc01139b4c1fb89b4c28232071a70853caab6d06 --- /dev/null +++ b/spider_gazebo/worlds/ramp2/model-1_2.sdf @@ -0,0 +1,25 @@ + + + + true + + 0 0 0.0 0 0 0 + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + diff --git a/spider_gazebo/worlds/ramp2/model-1_3.sdf b/spider_gazebo/worlds/ramp2/model-1_3.sdf new file mode 100644 index 0000000000000000000000000000000000000000..93af0338c2ad04564b0169db6ec2b70bf7beaef9 --- /dev/null +++ b/spider_gazebo/worlds/ramp2/model-1_3.sdf @@ -0,0 +1,25 @@ + + + + true + + 0 0 0.0 0 0 0 + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + diff --git a/spider_gazebo/worlds/ramp2/model-1_4.sdf b/spider_gazebo/worlds/ramp2/model-1_4.sdf new file mode 100644 index 0000000000000000000000000000000000000000..bfc527da2c5df393c21fafcd92527e853a0d5a80 --- /dev/null +++ b/spider_gazebo/worlds/ramp2/model-1_4.sdf @@ -0,0 +1,25 @@ + + + + true + + 0 0 0.0 0 0 0 + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + diff --git a/spider_gazebo/worlds/ramp2/model.config b/spider_gazebo/worlds/ramp2/model.config new file mode 100644 index 0000000000000000000000000000000000000000..0de6a61fd243c995c24c32efc8d96ed6b924105b --- /dev/null +++ b/spider_gazebo/worlds/ramp2/model.config @@ -0,0 +1,20 @@ + + + + NIST simple ramp 120 + 1.0 + model-1_2.sdf + model-1_3.sdf + model-1_4.sdf + model.sdf + + + Stefan Kohlbrecher + kohlbrecher@sim.tu-darmstadt.de + + + + 1.2m high NIST standard test arena simple ramp + + + diff --git a/spider_gazebo/worlds/ramp2/model.sdf b/spider_gazebo/worlds/ramp2/model.sdf new file mode 100644 index 0000000000000000000000000000000000000000..e19b6f3ec432c0f70497b3db201f9b31ed7ab2aa --- /dev/null +++ b/spider_gazebo/worlds/ramp2/model.sdf @@ -0,0 +1,25 @@ + + + + true + + 0 0 0.0 0 0 0 + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + + model://ramp2/meshes/nist_simple_ramp_120.dae + 10 10 10 + + + + + + diff --git a/spider_gazebo/worlds/spider.world b/spider_gazebo/worlds/spider.world index 0e93309b5a5b874345af759010eee37a1af006b9..c63192532712d613e4ca3329f62c3ea0f651ea97 100644 --- a/spider_gazebo/worlds/spider.world +++ b/spider_gazebo/worlds/spider.world @@ -2,48 +2,36 @@ - + model://sun + + + - - true - - - - - file://home/comp2/catkin_ws/src/spider/octapod_thesis/spider_gazebo/worlds/Antactica.tif - 150 150 50 - 0 0 -685 - - - - - - - - 2 - 5 - - - 4 - 5 - - file://home/comp2/catkin_ws/src/spider/octapod_thesis/spider_gazebo/worlds/Antactica.tif - 150 150 50 - 0 0 -685 - - - - - + + + model://apollo15_landing_site_1000x1000 + + 0.01 + 1 + 100 + 0 0 -1.622 + - - + + 4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190 @@ -53,3 +41,4 @@ +