diff --git a/cob_bringup/drivers/mimic.launch b/cob_bringup/drivers/mimic.launch
index cf2979b51..93cf1a1f7 100644
--- a/cob_bringup/drivers/mimic.launch
+++ b/cob_bringup/drivers/mimic.launch
@@ -2,6 +2,6 @@
-
+
diff --git a/cob_bringup/robots/cob4-2.xml b/cob_bringup/robots/cob4-2.xml
index 1fc766c74..b4d102261 100644
--- a/cob_bringup/robots/cob4-2.xml
+++ b/cob_bringup/robots/cob4-2.xml
@@ -85,6 +85,12 @@
+
+
+
+
+
+
@@ -204,9 +210,10 @@
-
+
+
diff --git a/cob_bringup/tools/android.launch b/cob_bringup/tools/android.launch
new file mode 100644
index 000000000..6aacc285e
--- /dev/null
+++ b/cob_bringup/tools/android.launch
@@ -0,0 +1,12 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/cob_bringup/tools/behavior.launch b/cob_bringup/tools/behavior.launch
new file mode 100644
index 000000000..25d6364aa
--- /dev/null
+++ b/cob_bringup/tools/behavior.launch
@@ -0,0 +1,9 @@
+
+
+
+
+
+
+
+
+
diff --git a/cob_bringup/tools/teleop.launch b/cob_bringup/tools/teleop.launch
index f98f9675e..de5759949 100644
--- a/cob_bringup/tools/teleop.launch
+++ b/cob_bringup/tools/teleop.launch
@@ -14,3 +14,4 @@
+
diff --git a/cob_default_robot_behavior/CMakeLists.txt b/cob_default_robot_behavior/CMakeLists.txt
new file mode 100644
index 000000000..70aae3a67
--- /dev/null
+++ b/cob_default_robot_behavior/CMakeLists.txt
@@ -0,0 +1,16 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(cob_default_robot_behavior)
+
+find_package(catkin REQUIRED COMPONENTS)
+
+catkin_package()
+
+set(robotlist
+ cob4-2
+)
+
+foreach(robot ${robotlist})
+ install(PROGRAMS scripts/trigger_srvs_${robot}.py
+ DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+ )
+endforeach()
diff --git a/cob_default_robot_behavior/package.xml b/cob_default_robot_behavior/package.xml
new file mode 100644
index 000000000..7129a2abb
--- /dev/null
+++ b/cob_default_robot_behavior/package.xml
@@ -0,0 +1,18 @@
+
+ cob_default_robot_behavior
+ 0.0.0
+ The cob_default_robot_behavior package
+
+ LGPL
+
+ Nadia Hammoudeh Garcia
+
+ catkin
+
+ cob_light
+ cob_script_server
+ rospy
+ std_msgs
+ std_srvs
+
+
diff --git a/cob_default_robot_behavior/scripts/trigger_srvs_cob4-2.py b/cob_default_robot_behavior/scripts/trigger_srvs_cob4-2.py
new file mode 100755
index 000000000..1df2b40c6
--- /dev/null
+++ b/cob_default_robot_behavior/scripts/trigger_srvs_cob4-2.py
@@ -0,0 +1,284 @@
+#!/usr/bin/python
+#################################################################
+##\file
+#
+# \note
+# Copyright (c) 2015 \n
+# Fraunhofer Institute for Manufacturing Engineering
+# and Automation (IPA) \n\n
+#
+#################################################################
+#
+# \note
+# Project name: care-o-bot
+# \note
+# ROS stack name: cob_robots
+# \note
+# ROS package name: cob_default_robot_behavior
+#
+# \author
+# Author: Nadia Hammoudeh Garcia, email:nadia.hammoudeh.garcia@ipa.fhg.de
+# \author
+# Supervised by: Nadia Hammoudeh Garcia, email:nadia.hammoudeh.garcia@ipa.fhg.de
+#
+# \date Date of creation: Aug 2015
+#
+# \brief
+# Implements script server functionalities.
+#
+#################################################################
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# - Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer. \n
+# - Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution. \n
+# - Neither the name of the Fraunhofer Institute for Manufacturing
+# Engineering and Automation (IPA) nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission. \n
+#
+# This program is free software: you can redistribute it and/or modify
+# it under the terms of the GNU Lesser General Public License LGPL as
+# published by the Free Software Foundation, either version 3 of the
+# License, or (at your option) any later version.
+#
+# This program is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU Lesser General Public License LGPL for more details.
+#
+# You should have received a copy of the GNU Lesser General Public
+# License LGPL along with this program.
+# If not, see .
+#
+#################################################################
+
+from cob_light.srv import *
+from cob_light.msg import *
+
+import rospy
+from simple_script_server import *
+sss = simple_script_server()
+from std_msgs.msg import ColorRGBA
+from std_srvs.srv import Trigger
+
+def torso_front_cb(req):
+ handle_arm_left = sss.move("arm_left","side", False)
+ handle_arm_right = sss.move("arm_right","side", False)
+ handle_arm_left.wait()
+ handle_arm_right.wait()
+ if handle_arm_left.get_error_code() == 0 and handle_arm_right.get_error_code() == 0:
+ sss.move_base_rel("base",[0,0,1.57],False)
+ sss.move("torso","front",True)
+
+ return
+
+def front_to_home_cb(req):
+ handle_arm_left = sss.move("arm_left","side", False)
+ handle_arm_right = sss.move("arm_right","side", False)
+ handle_arm_left.wait()
+ handle_arm_right.wait()
+ if handle_arm_left.get_error_code() == 0 and handle_arm_right.get_error_code() == 0:
+ sss.move_base_rel("base",[0,0,-1.57],False)
+ sss.move("torso","home",False)
+ return
+
+def pick_cb(req):
+ #sss.set_mimic("mimic",["asking",0,1])
+ sss.set_mimic("mimic",["happy",0,1])
+ handle_arm_left = sss.move("arm_left","side", False)
+ handle_arm_right = sss.move("arm_right","side", False)
+ #sss.set_mimic("mimic",["happy",0,1])
+ handle_arm_left.wait()
+ handle_arm_right.wait()
+ if handle_arm_left.get_error_code() == 0 and handle_arm_right.get_error_code() == 0:
+ sss.move("torso","front",False)
+ sss.move_base_rel("base",[0,0,1.57],False)
+ rospy.loginfo("------------------1 arm right movement")
+ handle_arm_right = sss.move("arm_right",[[1.2, 0.85, -1.0499900779997886, -1.660000104864327, -1.0499900779997886, -0.6999817498048457, 1.0699740979351238]], False)
+ sss.sleep(2)
+ sss.move_base_rel("base",[0,0,0.5],False)
+ rospy.loginfo("------------------2 arm right movement")
+ handle_arm_right = sss.move("arm_right",[[2.929779495567761, 0.9417796643761402, -2.5, -1.5, -0.28560567879635207, -0.41160099749782275, 0.2752035164544659]], False)
+ sss.sleep(2)
+ handle_arm_left = sss.move("arm_left",[[-0.9599, -1.5708, 0.12, -1.0, -1.38, -0.75, 1.36]], False)
+ sss.sleep(2)
+ rospy.loginfo("torso movement")
+ sss.move("torso",[[-3.14,2.7]],False)
+ handle_arm_right = sss.move("arm_right",[[2.9300063883705207, 0.41079814604190534, -2.4999747139716377, -1.4999883190414864, -0.2899864552188579, -0.40999529458598793, 0.2800031718974503]], True)
+ handle_arm_right = sss.move("arm_right",[[2.929988935078001, 0.9391791237906687, -2.940007124984448, -0.8784067592362261, -0.2899864552188579, -0.23357741379440114, 0.2800031718974503]], True)
+ sss.sleep(3)
+ #move right arm
+ #open the gripper
+
+ ##RETURN
+
+
+ handle_arm_right = sss.move("arm_right",[[2.9300063883705207, 0.41079814604190534, -2.4999747139716377, -1.4999883190414864, -0.2899864552188579, -0.40999529458598793, 0.2800031718974503]],True)
+ #sss.sleep(1)
+ sss.move("torso","front",False)
+ handle_arm_right = sss.move("arm_right",[[2.929779495567761, 0.9417796643761402, -2.5, -1.5, -0.28560567879635207, -0.41160099749782275, 0.2752035164544659]], False)
+ sss.move_base_rel("base",[0,0,-0.3],False)
+ sss.sleep(2)
+ sss.move("torso","home",False)
+ handle_arm_right = sss.move("arm_right",[[1.2, 0.85, -1.0499900779997886, -1.660000104864327, -1.0499900779997886, -0.6999817498048457, 1.0699740979351238]], False)
+ handle_base = sss.move_base_rel("base",[0,0,-1.2],False)
+ sss.sleep(2)
+ handle_arm_left = sss.move("arm_left","side", False)
+ handle_arm_right = sss.move("arm_right","side", False)
+ sss.set_mimic("mimic",["blinking_right",0,1])
+ handle_base.wait()
+
+ return
+
+def setLightCyan_cb(req):
+ sss.set_light("light_base","cyan")
+ sss.set_light("light_torso","cyan")
+ return
+
+def setLightRed_cb(req):
+ sss.set_light("light_base","red")
+ sss.set_light("light_torso","red")
+ return
+
+def setLightGreen_cb(req):
+ sss.set_light("light_base","green")
+ sss.set_light("light_torso","green")
+ return
+
+def setLightCyanSweep_cb(req):
+ #rospy.wait_for_service('/light_torso/set_light')
+ sss.set_light("light_base","cyan")
+
+ try:
+ set_light_torso = rospy.ServiceProxy("/light_torso/set_light",SetLightMode)
+ light_mode = LightMode()
+ cyan_color = ColorRGBA()
+ cyan_color.r = 0.0
+ cyan_color.g = 1.0
+ cyan_color.b = 0.5
+ cyan_color.a = 0.4
+ light_mode.colors.append(cyan_color)
+ light_mode.mode = 8
+ light_mode.frequency = 30
+ resp = set_light_torso(light_mode)
+ print resp
+ return
+ except rospy.ServiceException, e:
+ print "Service call failed: %s"%e
+
+def setLightCyanBreath_cb(req):
+ #rospy.wait_for_service('/light_torso/set_light')
+ sss.set_light("light_base","cyan")
+
+ try:
+ set_light_torso = rospy.ServiceProxy("/light_torso/set_light",SetLightMode)
+ light_mode = LightMode()
+ cyan_color = ColorRGBA()
+ cyan_color.r = 0.0
+ cyan_color.g = 1.0
+ cyan_color.b = 0.5
+ cyan_color.a = 0.4
+ light_mode.color = cyan_color
+ light_mode.mode = 3
+ light_mode.frequency = 0.25
+ resp = set_light_torso(light_mode)
+ print resp
+ return
+ except rospy.ServiceException, e:
+ print "Service call failed: %s"%e
+
+
+def setMimicLaughing_cb(req):
+ sss.set_mimic("mimic",["laughing",0,1])
+ return
+
+def setMimicAsking_cb(req):
+ sss.set_mimic("mimic",["asking",0,1])
+ return
+
+def setMimicYes_cb(req):
+ sss.set_mimic("mimic",["yes",0,1])
+ return
+
+def setMimicBlinkingRight_cb(req):
+ sss.set_mimic("mimic",["blinking_right",0,1])
+ return
+
+def setMimicConfused_cb(req):
+ sss.set_mimic("mimic",["confused",0,1])
+ return
+
+def setMimicAngry_cb(req):
+ sss.set_mimic("mimic",["angry",0,1])
+ return
+
+def setMimicFallingAsleep_cb(req):
+ sss.set_mimic("mimic",["falling_asleep",0,1])
+ return
+
+def soundR2D2_cb(req):
+ sss.play("R2D2")
+ return
+
+def showCamera_left_cb(req):
+ sss.move("arm_left",[[-1.7642137145009082, -1.2919974320813223, 1.3, 1.8777473823431394, -0.0, -0.24, -0.0]])
+ sss.move("gripper_left","open")
+ return
+
+def showCamera_right_cb(req):
+ sss.move("arm_right",[[1.7642137145009082, 1.2919974320813223, -1.3, -1.8777473823431394, 0.0, 0.24, 0.0]])
+ sss.move("gripper_right","open")
+ return
+
+def soundNoConnection_cb(req):
+ sss.set_mimic("mimic",["confused",0,1])
+ sss.play("confused")
+ return
+
+def soundNegative_cb(req):
+ sss.play("negative")
+ return
+
+def soundStarting_cb(req):
+ sss.play("starting")
+ return
+
+def soundHello_cb(req):
+ sss.say(["Hello, my name is Care O bot, a mobile service robot from Fraunhofer I.P.A."])
+ sss.say(["I am at your command."])
+ return
+
+def trigger_srvs():
+ rospy.init_node('trigger_srvs')
+ s = rospy.Service('/behavior/torso_front', Trigger, torso_front_cb)
+ s = rospy.Service('/behavior/torso_front_home', Trigger, front_to_home_cb)
+ s = rospy.Service('/behavior/pick', Trigger, pick_cb)
+ s = rospy.Service('/behavior/setLightCyan', Trigger, setLightCyan_cb)
+ s = rospy.Service('/behavior/setLightRed', Trigger, setLightRed_cb)
+ s = rospy.Service('/behavior/setLightGreen', Trigger, setLightGreen_cb)
+ s = rospy.Service('/behavior/setLightCyanSweep', Trigger, setLightCyanSweep_cb)
+ s = rospy.Service('/behavior/setLightCyanBreath', Trigger, setLightCyanBreath_cb)
+ s = rospy.Service('/behavior/setMimicLaughing', Trigger, setMimicLaughing_cb)
+ s = rospy.Service('/behavior/setMimicAsking', Trigger, setMimicAsking_cb)
+ s = rospy.Service('/behavior/setMimicYes', Trigger, setMimicYes_cb)
+ s = rospy.Service('/behavior/setMimicBlinkingRight', Trigger, setMimicBlinkingRight_cb)
+ s = rospy.Service('/behavior/setMimicConfused', Trigger, setMimicConfused_cb)
+ s = rospy.Service('/behavior/setMimicAngry', Trigger, setMimicAngry_cb)
+ s = rospy.Service('/behavior/setMimicFallingAsleep', Trigger, setMimicFallingAsleep_cb)
+ s = rospy.Service('/behavior/soundR2D2', Trigger, soundR2D2_cb)
+ s = rospy.Service('/behavior/soundNoConnection',Trigger,soundNoConnection_cb)
+ s = rospy.Service('/behavior/soundNegative',Trigger,soundNegative_cb)
+ s = rospy.Service('/behavior/soundStarting',Trigger,soundStarting_cb)
+ s = rospy.Service('/behavior/soundHello',Trigger,soundHello_cb)
+ s = rospy.Service('/gripper_left/driver/showCamera_left',Trigger, showCamera_left_cb)
+ s = rospy.Service('/gripper_right/driver/showCamera_right',Trigger, showCamera_right_cb)
+
+ rospy.spin()
+
+if __name__ == "__main__":
+ trigger_srvs()
diff --git a/cob_default_robot_config/cob4-2/arm_left_joint_configurations.yaml b/cob_default_robot_config/cob4-2/arm_left_joint_configurations.yaml
index 5a4cccdac..aba3962a6 100644
--- a/cob_default_robot_config/cob4-2/arm_left_joint_configurations.yaml
+++ b/cob_default_robot_config/cob4-2/arm_left_joint_configurations.yaml
@@ -8,3 +8,15 @@ home: [[0,0,0,0,0,0,0]]
folded: [[0.9599, 1.5708, -0.1200, 1.0000, 1.3800, 0.7500, -1.3600]]
side: [[-0.9599, -1.6581, 1.0472, 1.6581, 1.0472, 0.6981, -1.0700]]
ship: [[0.0, 0.0, 0.0, 1.57, 0.0, 0.0, 0.0]]
+
+hello1: [[-1.69,-1.19,0.48,2.09,0.34,-0.16,-0.12]]
+hello2 : [[-1.69, -1.19, 0.48, 2.61, 0.34, 0.38, 0.5]]
+arm_to_tray : [[1.06, 1.2, -1.4, 1.9, -1.84, -1.12, -0.64]]
+
+hello: [hello1, hello2, hello1, hello2, side]
+
+wave1: [[-1.5, 0, 0, 0, 0, 0, 0]]
+wave2: [[-1.5, 0.3, 0, -1, 0, 0.7, 0]]
+wave3: [[-1.5, -0.3, 0, 1, 0, -0.7, 0]]
+
+wave_demo: [side,home,wave1,wave2,wave3,wave2,wave1,home,side]
\ No newline at end of file
diff --git a/cob_default_robot_config/cob4-2/arm_right_joint_configurations.yaml b/cob_default_robot_config/cob4-2/arm_right_joint_configurations.yaml
index 49596b4e1..c337426c0 100644
--- a/cob_default_robot_config/cob4-2/arm_right_joint_configurations.yaml
+++ b/cob_default_robot_config/cob4-2/arm_right_joint_configurations.yaml
@@ -8,3 +8,16 @@ home: [[0,0,0,0,0,0,0]]
folded: [[0.9599, 1.5708, -0.1200, 1.0000, 1.3800, 0.7500, -1.3600]]
side: [[0.9599, 1.6581, -1.0472, -1.6581, -1.0472, -0.6981, 1.0700]]
ship: [[0.0, 0.0, 0.0, 1.57, 0.0, 0.0, 0.0]]
+
+hello1: [[1.69,1.19,-0.48,-2.09,-0.34,0.16,0.12]]
+hello2 : [[1.69, 1.19, -0.48, -2.61, -0.34, -0.38, -0.5]]
+arm_to_tray : [[-1.06, -1.2, 1.4, -1.9, 1.84, 1.12, 0.64]]
+show_gripper : [[1.76, 1.29, -1.53, -1.88, 0.0, 0.0, 0.0]]
+
+hello: [hello1, hello2, hello1, hello2, side]
+
+wave1: [[1.5, 0, 0, 0, 0, 0, 0]]
+wave2: [[1.5, 0.3, 0, -1, 0, 0.7, 0]]
+wave3: [[1.5, -0.3, 0, 1, 0, -0.7, 0]]
+
+wave_demo: [side,home,wave1,wave2,wave3,wave2,wave1,home,side]
\ No newline at end of file
diff --git a/cob_default_robot_config/cob4-2/behavior.yaml b/cob_default_robot_config/cob4-2/behavior.yaml
new file mode 100644
index 000000000..b9d36852d
--- /dev/null
+++ b/cob_default_robot_config/cob4-2/behavior.yaml
@@ -0,0 +1 @@
+service_ns: /behavior
diff --git a/cob_default_robot_config/cob4-2/command_gui_buttons.yaml b/cob_default_robot_config/cob4-2/command_gui_buttons.yaml
index 3e7b227b4..874de7974 100644
--- a/cob_default_robot_config/cob4-2/command_gui_buttons.yaml
+++ b/cob_default_robot_config/cob4-2/command_gui_buttons.yaml
@@ -4,20 +4,13 @@
# buttons: [[button_name1,function_name1,parameter_name2,
# [button_name2,function_name2,parameter_name2]]
-group1:
+group10:
group_name: base
component_name: base
buttons: [[stop,stop,omni],
[init,trigger,init],
[recover,trigger,recover]]
-#group2:
-# group_name: torso
-# component_name: torso
-# buttons: [[stop,trigger,stop],
-# [init,trigger,init],
-# [recover,trigger,recover],
-# [home,move,home]]
-group4:
+group11:
group_name: sensorring
component_name: sensorring
buttons: [[stop,stop],
@@ -27,7 +20,7 @@ group4:
[back,move,back],
[left,move,left],
[right,move,right]]
-group5:
+group12:
group_name: arm_left
component_name: arm_left
buttons: [[stop,stop],
@@ -35,8 +28,11 @@ group5:
[recover,recover],
[home,move,home],
[folded,move,folded],
- [side, move, side]]
-group6:
+ [side, move, side],
+ [ship, move, ship],
+ [wave_demo, move, wave_demo],
+ [hello, move, hello]]
+group13:
group_name: arm_right
component_name: arm_right
buttons: [[stop,stop],
@@ -44,20 +40,62 @@ group6:
[recover,recover],
[home,move,home],
[folded,move,folded],
- [side, move, side]]
-group7:
- group_name: gripper_left
- component_name: gripper_left
- buttons: [[stop,stop],
- [recover,recover],
- [home,move,home],
- [open,move,open],
- [close, move, close]]
-group8:
- group_name: gripper_right
- component_name: gripper_right
- buttons: [[stop,stop],
- [recover,recover],
- [home,move,home],
- [open,move,open],
- [close, move, close]]
+ [side, move, side],
+ [ship, move, ship],
+ [wave_demo, move, wave_demo],
+ [hello, move, hello]]
+#group14:
+# group_name: gripper_left
+# component_name: gripper_left
+# buttons: [[stop,stop],
+# [recover,recover],
+# [home,move,home],
+# [open,move,open],
+# [close, move, close]]
+#group15:
+# group_name: gripper_right
+# component_name: gripper_right
+# buttons: [[stop,stop],
+# [recover,recover],
+# [home,move,home],
+# [open,move,open],
+# [close, move, close]]
+group16:
+ group_name: torso
+ component_name: torso
+ buttons: [[stop,trigger,stop],
+ [init,trigger,init],
+ [recover,trigger,recover],
+ [home,move,home]]
+group17:
+ group_name: torso
+ component_name: behavior
+ buttons: [[torso_front,trigger,torso_front],
+ [torso_front_home,trigger,torso_front_home],
+ [pick,trigger,pick]]
+group21:
+ group_name: mimic
+ component_name: behavior
+ buttons: [[laughing,trigger,setMimicLaughing],
+ [asking,trigger,setMimicAsking],
+ [SayYes,trigger,setMimicYes],
+ [blinkingRight,trigger,setMimicBlinkingRight],
+ [confused,trigger,setMimicConfused],
+ [angry,trigger,setMimicAngry],
+ [sleep,trigger,setMimicFallingAsleep]]
+group22:
+ group_name: light
+ component_name: behavior
+ buttons: [[cyanBreath,trigger,setLightCyanBreath],
+ [cyan,trigger,setLightCyan],
+ [red,trigger,setLightRed],
+ [green,trigger,setLightGreen],
+ [cyanSweep,trigger,setLightCyanSweep]]
+group23:
+ group_name: sound
+ component_name: behavior
+ buttons: [[playSound,trigger,playSound],
+ [noConnection,trigger,soundNoConnection],
+ [negative,trigger,soundNegative],
+ [starting,trigger,soundStarting],
+ [hello,trigger,soundHello]]
diff --git a/cob_default_robot_config/cob4-2/sound.yaml b/cob_default_robot_config/cob4-2/sound.yaml
new file mode 100644
index 000000000..476e26da6
--- /dev/null
+++ b/cob_default_robot_config/cob4-2/sound.yaml
@@ -0,0 +1 @@
+audio_file_path: /u/robot/sounds
diff --git a/cob_default_robot_config/cob4-2/torso_joint_configurations.yaml b/cob_default_robot_config/cob4-2/torso_joint_configurations.yaml
index ef9bb7174..c9d9f50a0 100644
--- a/cob_default_robot_config/cob4-2/torso_joint_configurations.yaml
+++ b/cob_default_robot_config/cob4-2/torso_joint_configurations.yaml
@@ -3,6 +3,6 @@ action_name: /torso/joint_trajectory_controller/follow_joint_trajectory
service_ns: /torso/driver
default_vel: 0.4
-home: [[0.0, 0.0]]
+home: [[0.0,0.0]]
front: [[-3.14,1.57]]
back : [[3.14,-1.57]]
diff --git a/cob_default_robot_config/cob4-2/upload_param_cob4-2.launch b/cob_default_robot_config/cob4-2/upload_param_cob4-2.launch
index 23d964202..e27c6ec92 100644
--- a/cob_default_robot_config/cob4-2/upload_param_cob4-2.launch
+++ b/cob_default_robot_config/cob4-2/upload_param_cob4-2.launch
@@ -12,5 +12,7 @@
+
+
diff --git a/cob_hardware_config/cob4-2/config/base_controller.yaml b/cob_hardware_config/cob4-2/config/base_controller.yaml
index 0e2b5fec7..2b449c577 100644
--- a/cob_hardware_config/cob4-2/config/base_controller.yaml
+++ b/cob_hardware_config/cob4-2/config/base_controller.yaml
@@ -35,3 +35,14 @@ odometry_controller:
type: cob_omni_drive_controller/OdometryController
publish_rate: 50
wheels: *wheels
+
+joint_group_velocity_controller:
+ type: velocity_controllers/JointGroupVelocityController
+ joints:
+ - fl_caster_rotation_joint
+ - fl_caster_r_wheel_joint
+ - bl_caster_rotation_joint
+ - bl_caster_r_wheel_joint
+ - br_caster_rotation_joint
+ - br_caster_r_wheel_joint
+ required_drive_mode: 2
diff --git a/cob_hardware_config/cob4-2/config/diagnostics_analyzers.yaml b/cob_hardware_config/cob4-2/config/diagnostics_analyzers.yaml
index 4029ac036..6473160ef 100644
--- a/cob_hardware_config/cob4-2/config/diagnostics_analyzers.yaml
+++ b/cob_hardware_config/cob4-2/config/diagnostics_analyzers.yaml
@@ -80,19 +80,19 @@ analyzers:
torso:
type: diagnostic_aggregator/GenericAnalyzer
path: Torso
- contains: 'torso'
+ contains: 'torso_driver'
sensorring:
type: diagnostic_aggregator/GenericAnalyzer
path: Sensorring
- contains: 'sensorring'
+ contains: 'sensorring_driver'
arm_right:
type: diagnostic_aggregator/GenericAnalyzer
path: Arm Right
- contains: 'arm_right'
+ contains: 'arm_right_driver'
arm_left:
type: diagnostic_aggregator/GenericAnalyzer
path: Arm Left
- contains: 'arm_left'
+ contains: 'arm_left_driver'
base:
type: diagnostic_aggregator/GenericAnalyzer
path: Base
diff --git a/cob_hardware_config/cob4-2/config/teleop.yaml b/cob_hardware_config/cob4-2/config/teleop.yaml
index 7a1cc0488..998417043 100644
--- a/cob_hardware_config/cob4-2/config/teleop.yaml
+++ b/cob_hardware_config/cob4-2/config/teleop.yaml
@@ -6,7 +6,7 @@ joy_num_buttons: 12
joy_num_axes: 6
joy_num_modes: 4
mode_switch_button: 8
-light_topic_name: /light_torso/light
+light_action_name: /light_torso/set_light
# axes
axis_vx: 1
diff --git a/cob_hardware_config/cob4-4/cob4-4.rviz b/cob_hardware_config/cob4-4/cob4-4.rviz
new file mode 120000
index 000000000..565746e47
--- /dev/null
+++ b/cob_hardware_config/cob4-4/cob4-4.rviz
@@ -0,0 +1 @@
+../common/cob4_base.rviz
\ No newline at end of file
diff --git a/cob_hardware_config/cob4-4/config/Elmo.dcf b/cob_hardware_config/cob4-4/config/Elmo.dcf
deleted file mode 100644
index a09efd8db..000000000
--- a/cob_hardware_config/cob4-4/config/Elmo.dcf
+++ /dev/null
@@ -1,4502 +0,0 @@
-[FileInfo]
-CreatedBy=Vladyslav Nechayev
-ModifiedBy=Vladyslav Nechayev
-Description=Elmo Gold drive EDS file
-CreationTime=07:53AM
-CreationDate=05-11-2014
-ModificationTime=07:53AM
-ModificationDate=05-11-2014
-FileName=CANeds Gold V002.eds
-FileVersion=002
-FileRevision=01
-EDSVersion=4.0
-
-[DeviceInfo]
-VendorName=Elmo Motion Control
-VendorNumber=0x0000009A
-ProductName=Gold Drive
-ProductNumber=0x00030923
-RevisionNumber=0x000103F6
-OrderCode=1
-BaudRate_10=0
-BaudRate_20=0
-BaudRate_50=1
-BaudRate_125=1
-BaudRate_250=1
-BaudRate_500=1
-BaudRate_800=0
-BaudRate_1000=1
-SimpleBootUpMaster=0
-SimpleBootUpSlave=0
-Granularity=8
-DynamicChannelsSupported=0
-CompactPDO=23
-GroupMessaging=0
-NrOfRXPDO=4
-NrOfTXPDO=4
-LSS_Supported=0
-
-[DummyUsage]
-Dummy0001=0
-Dummy0002=0
-Dummy0003=0
-Dummy0004=0
-Dummy0005=1
-Dummy0006=0
-Dummy0007=0
-
-[Comments]
-Lines=7
-Line1=CANeds Gold V001.eds29/10/2013
-Line2=First release
-Line3=
-Line4=CANeds Gold V002.eds 11/05/2014
-Line5=1. Added 100K baud to Device Information
-Line6=2. 6089,608A,608B,608D, 6093, 6094, 6095 were removed: not in use
-Line7=3. 6075, 6076, 603F 60C4 sub 6, 60FD default values were modified to 0.
-
-[MandatoryObjects]
-SupportedObjects=3
-1=0x1000
-2=0x1001
-3=0x1018
-
-[1000]
-ParameterName=Device Type
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0x192
-PDOMapping=0
-
-[1001]
-ParameterName=Error Register
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1018]
-ParameterName=Identity Object
-ObjectType=0x9
-SubNumber=5
-
-[1018sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=4
-PDOMapping=0
-LowLimit=1
-HighLimit=4
-
-[1018sub1]
-ParameterName=Vendor Id
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0x0000009A
-PDOMapping=0
-
-[1018sub2]
-ParameterName=Product Code
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=0
-
-[1018sub3]
-ParameterName=Revision number
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=0
-
-[1018sub4]
-ParameterName=Serial number
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=0
-
-[OptionalObjects]
-SupportedObjects=119
-1=0x1002
-2=0x1003
-3=0x1006
-4=0x1008
-5=0x1009
-6=0x100A
-7=0x100B
-8=0x1010
-9=0x1011
-10=0x1014
-11=0x1016
-12=0x1017
-13=0x1023
-14=0x1024
-15=0x1029
-16=0x1400
-17=0x1401
-18=0x1402
-19=0x1403
-20=0x1600
-21=0x1601
-22=0x1602
-23=0x1603
-24=0x1800
-25=0x1801
-26=0x1802
-27=0x1803
-28=0x1A00
-29=0x1A01
-30=0x1A02
-31=0x1A03
-32=0x6007
-33=0x603F
-34=0x6040
-35=0x6041
-36=0x605A
-37=0x605B
-38=0x605C
-39=0x605D
-40=0x605E
-41=0x6060
-42=0x6061
-43=0x6062
-44=0x6063
-45=0x6064
-46=0x6065
-47=0x6066
-48=0x6067
-49=0x6068
-50=0x6069
-51=0x606A
-52=0x606B
-53=0x606C
-54=0x606D
-55=0x606E
-56=0x606F
-57=0x6070
-58=0x6071
-59=0x6072
-60=0x6073
-61=0x6074
-62=0x6075
-63=0x6076
-64=0x6077
-65=0x6078
-66=0x6079
-67=0x607A
-68=0x607B
-69=0x607C
-70=0x607D
-71=0x607E
-72=0x607F
-73=0x6080
-74=0x6081
-75=0x6082
-76=0x6083
-77=0x6084
-78=0x6085
-79=0x6086
-80=0x6087
-81=0x608C
-82=0x608E
-83=0x608F
-84=0x6090
-85=0x6091
-86=0x6092
-87=0x6096
-88=0x6097
-89=0x6098
-90=0x6099
-91=0x609A
-92=0x60B0
-93=0x60B1
-94=0x60B2
-95=0x60B8
-96=0x60B9
-97=0x60BA
-98=0x60BB
-99=0x60BC
-100=0x60BD
-101=0x60C0
-102=0x60C1
-103=0x60C2
-104=0x60C4
-105=0x60C5
-106=0x60C6
-107=0x60E0
-108=0x60E1
-109=0x60E3
-110=0x60E4
-111=0x60E5
-112=0x60F2
-113=0x60F4
-114=0x60FA
-115=0x60FC
-116=0x60FD
-117=0x60FE
-118=0x60FF
-119=0x6502
-
-[1002]
-ParameterName=Manufacturer Status Register
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=0
-
-[1003]
-ParameterName=Predefined Error Field
-ObjectType=0x8
-SubNumber=17
-
-[1003sub0]
-ParameterName=Number of Errors
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[1003sub1]
-ParameterName=Standard Error Field
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub2]
-ParameterName=Standard Error Field_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub3]
-ParameterName=Standard Error Field_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub4]
-ParameterName=Standard Error Field_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub5]
-ParameterName=Standard Error Field_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub6]
-ParameterName=Standard Error Field_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub7]
-ParameterName=Standard Error Field_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub8]
-ParameterName=Standard Error Field_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub9]
-ParameterName=Standard Error Field_9
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subA]
-ParameterName=Standard Error Field_a
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subB]
-ParameterName=Standard Error Field_b
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subC]
-ParameterName=Standard Error Field_c
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subD]
-ParameterName=Standard Error Field_d
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subE]
-ParameterName=Standard Error Field_e
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003subF]
-ParameterName=Standard Error Field_f
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1003sub10]
-ParameterName=Standard Error Field_10
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[1006]
-ParameterName=Communication Cycle Period
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[1008]
-ParameterName=Manufacturer Device Name
-ObjectType=0x7
-DataType=0x0009
-AccessType=const
-PDOMapping=0
-
-[1009]
-ParameterName=Manufacturer Hardware Version
-ObjectType=0x7
-DataType=0x0009
-AccessType=const
-PDOMapping=0
-
-[100A]
-ParameterName=Manufacturer Software Version
-ObjectType=0x7
-DataType=0x0009
-AccessType=const
-PDOMapping=0
-
-[100B]
-ParameterName=CAN Open Node ID
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-LowLimit=1
-HighLimit=127
-
-[1010]
-ParameterName=Store Parameters
-ObjectType=0x8
-SubNumber=2
-
-[1010sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=0x0
-HighLimit=0x7F
-
-[1010sub1]
-ParameterName=Save all Parameters
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1011]
-ParameterName=Restore Default Parameters
-ObjectType=0x8
-SubNumber=2
-
-[1011sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=0x0
-HighLimit=0x7F
-
-[1011sub1]
-ParameterName=Restore all Default Parameters
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1014]
-ParameterName=COB ID EMCY
-ObjectType=0x7
-DataType=0x0007
-AccessType=const
-DefaultValue=$NODEID+0x80
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-
-[1016]
-ParameterName=Consumer Heartbeat Time
-ObjectType=0x8
-SubNumber=3
-
-[1016sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0x1
-HighLimit=0x2
-
-[1016sub1]
-ParameterName=Consumer Heartbeat Time
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1016sub2]
-ParameterName=Consumer Heartbeat Time_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1017]
-ParameterName=Producer Heartbeat Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1023]
-ParameterName=OS Command
-ObjectType=0x9
-SubNumber=4
-
-[1023sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=3
-PDOMapping=0
-LowLimit=1
-HighLimit=3
-
-[1023sub1]
-ParameterName=Command
-ObjectType=0x7
-DataType=0x000a
-AccessType=wo
-PDOMapping=0
-
-[1023sub2]
-ParameterName=Status
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=255
-
-[1023sub3]
-ParameterName=Reply
-ObjectType=0x7
-DataType=0x000a
-AccessType=ro
-PDOMapping=0
-
-[1024]
-ParameterName=OS Command Mode
-ObjectType=0x7
-DataType=0x0005
-AccessType=wo
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=3
-
-[1029]
-ParameterName=Error behaviour
-ObjectType=0x8
-SubNumber=2
-
-[1029sub0]
-ParameterName=Nr of Error Classes
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-
-[1029sub1]
-ParameterName=Communication Error
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[1400]
-ParameterName=Receive PDO Communication Parameter 0
-ObjectType=0x9
-SubNumber=3
-
-[1400sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1400sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x200
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-ParameterValue=$NODEID+0x200
-
-[1400sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-ParameterValue=0x1
-
-[1401]
-ParameterName=Receive PDO Communication Parameter 1
-ObjectType=0x9
-SubNumber=3
-
-[1401sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1401sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x300
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-
-[1401sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-
-[1402]
-ParameterName=Receive PDO Communication Parameter 2
-ObjectType=0x9
-SubNumber=3
-
-[1402sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1402sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x400
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-ParameterValue=$NODEID+0x400
-
-[1402sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-ParameterValue=0x1
-
-[1403]
-ParameterName=Receive PDO Communication Parameter 3
-ObjectType=0x9
-SubNumber=3
-
-[1403sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1403sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x500
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-ParameterValue=$NODEID+0x500
-
-[1403sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-ParameterValue=0x1
-
-[1600]
-ParameterName=Receive PDO Mapping Parameter 0
-ObjectType=0x9
-SubNumber=9
-
-[1600sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-ParameterValue=2
-
-[1600sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x60400010
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-ParameterValue=0x60400010
-
-[1600sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60600008
-
-[1600sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1600sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1600sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1600sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1600sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1600sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601]
-ParameterName=Receive PDO Mapping Parameter 1
-ObjectType=0x9
-SubNumber=9
-
-[1601sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-
-[1601sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x20120020
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[1601sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1601sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602]
-ParameterName=Receive PDO Mapping Parameter 2
-ObjectType=0x9
-SubNumber=9
-
-[1602sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-ParameterValue=2
-
-[1602sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x607a0020
-
-[1602sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60ff0020
-
-[1602sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1602sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603]
-ParameterName=Receive PDO Mapping Parameter 3
-ObjectType=0x9
-SubNumber=9
-
-[1603sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-ParameterValue=2
-
-[1603sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60c10120
-
-[1603sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60c10220
-
-[1603sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1603sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1800]
-ParameterName=Transmit PDO Communication Parameter 0
-ObjectType=0x9
-SubNumber=6
-
-[1800sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=5
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1800sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x180
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-ParameterValue=$NODEID+0x180
-
-[1800sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-ParameterValue=0x1
-
-[1800sub3]
-ParameterName=Inhibit Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0x0000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1800sub4]
-ParameterName=Reserved
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-
-[1800sub5]
-ParameterName=Event Timer
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1801]
-ParameterName=Transmit PDO Communication Parameter 1
-ObjectType=0x9
-SubNumber=6
-
-[1801sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=5
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1801sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x280
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-
-[1801sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[1801sub3]
-ParameterName=Inhibit Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0x0000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1801sub4]
-ParameterName=Reserved
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-
-[1801sub5]
-ParameterName=Event Timer
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1802]
-ParameterName=Transmit PDO Communication Parameter 2
-ObjectType=0x9
-SubNumber=6
-
-[1802sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=5
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1802sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x380
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-ParameterValue=$NODEID+0x380
-
-[1802sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-ParameterValue=0x1
-
-[1802sub3]
-ParameterName=Inhibit Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0x0000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1802sub4]
-ParameterName=Reserved
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-
-[1802sub5]
-ParameterName=Event Timer
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1803]
-ParameterName=Transmit PDO Communication Parameter 3
-ObjectType=0x9
-SubNumber=6
-
-[1803sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=5
-PDOMapping=0
-LowLimit=0x02
-HighLimit=0x05
-
-[1803sub1]
-ParameterName=COB ID
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=$NODEID+0x480
-PDOMapping=0
-LowLimit=0x00000001
-HighLimit=0xFFFFFFFF
-
-[1803sub2]
-ParameterName=Transmission Type
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=255
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[1803sub3]
-ParameterName=Inhibit Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0x0000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1803sub4]
-ParameterName=Reserved
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-
-[1803sub5]
-ParameterName=Event Timer
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[1A00]
-ParameterName=Transmit PDO Mapping Parameter 0
-ObjectType=0x9
-SubNumber=9
-
-[1A00sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-ParameterValue=2
-
-[1A00sub1]
-ParameterName=Status Word
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x60410010
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-ParameterValue=0x60410010
-
-[1A00sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60610008
-
-[1A00sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A00sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A00sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A00sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A00sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A00sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01]
-ParameterName=Transmit PDO Mapping Parameter 1
-ObjectType=0x9
-SubNumber=9
-
-[1A01sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-
-[1A01sub1]
-ParameterName=Binary Interpreter Output
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x20130040
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[1A01sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A01sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02]
-ParameterName=Transmit PDO Mapping Parameter 2
-ObjectType=0x9
-SubNumber=9
-
-[1A02sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-ParameterValue=2
-
-[1A02sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x60640020
-
-[1A02sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-ParameterValue=0x606c0020
-
-[1A02sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A02sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03]
-ParameterName=Transmit PDO Mapping Parameter 3
-ObjectType=0x9
-SubNumber=9
-
-[1A03sub0]
-ParameterName=Number of entries
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=8
-
-[1A03sub1]
-ParameterName=PDO Mapping Entry
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub2]
-ParameterName=PDO Mapping Entry_2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub3]
-ParameterName=PDO Mapping Entry_3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub4]
-ParameterName=PDO Mapping Entry_4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub5]
-ParameterName=PDO Mapping Entry_5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub6]
-ParameterName=PDO Mapping Entry_6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub7]
-ParameterName=PDO Mapping Entry_7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[1A03sub8]
-ParameterName=PDO Mapping Entry_8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[6007]
-ParameterName=abort_connection_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=3
-
-[603F]
-ParameterName=error_code
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6040]
-ParameterName=controlword
-ObjectType=0x7
-DataType=0x0006
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFF
-
-[6041]
-ParameterName=statusword
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFF
-
-[605A]
-ParameterName=quick_stop_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=2
-PDOMapping=0
-LowLimit=-32768
-HighLimit=8
-
-[605B]
-ParameterName=shutdown_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[605C]
-ParameterName=disable_operation_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[605D]
-ParameterName=halt_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=2
-PDOMapping=0
-LowLimit=1
-HighLimit=2
-
-[605E]
-ParameterName=fault_reaction_option_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=2
-PDOMapping=0
-LowLimit=0
-HighLimit=2
-
-[6060]
-ParameterName=modes_of_operation
-ObjectType=0x7
-DataType=0x0002
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-128
-HighLimit=10
-
-[6061]
-ParameterName=modes_of_operation_display
-ObjectType=0x7
-DataType=0x0002
-AccessType=ro
-PDOMapping=1
-LowLimit=0
-HighLimit=10
-
-[6062]
-ParameterName=position_demand_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[6063]
-ParameterName=position_actual_internal_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[6064]
-ParameterName=position_actual_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[6065]
-ParameterName=following_error_window
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6066]
-ParameterName=following_error_time_out
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=20
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6067]
-ParameterName=position_window
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=100
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6068]
-ParameterName=position_window_time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=20
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6069]
-ParameterName=velocity_sensor_actual_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[606A]
-ParameterName=sensor_selection_code
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[606B]
-ParameterName=velocity_demand_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[606C]
-ParameterName=velocity_actual_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[606D]
-ParameterName=velocity_window
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=100
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[606E]
-ParameterName=velocity_window_time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=20
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[606F]
-ParameterName=velocity_threshold
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=100
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6070]
-ParameterName=velocity_threshold_time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=20
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6071]
-ParameterName=target_torque
-ObjectType=0x7
-DataType=0x0003
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-32768
-HighLimit=32767
-
-[6072]
-ParameterName=max_torque
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=50000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6073]
-ParameterName=max_current
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=50000
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[6074]
-ParameterName=torque_demand
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-32768
-HighLimit=32767
-
-[6075]
-ParameterName=motor_rated_current
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6076]
-ParameterName=motor_rated_torque
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6077]
-ParameterName=torque_actual_value
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-32768
-HighLimit=32767
-
-[6078]
-ParameterName=current_actual_value
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-32768
-HighLimit=32767
-
-[6079]
-ParameterName=dc_link_circuit_voltage
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[607A]
-ParameterName=target_position
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607B]
-ParameterName=position_range_limit
-ObjectType=0x8
-SubNumber=3
-
-[607Bsub0]
-ParameterName=position_range_limit_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[607Bsub1]
-ParameterName=position_range_limit_min
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=-1000000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607Bsub2]
-ParameterName=position_range_limit_max
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=1000000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607C]
-ParameterName=home_offset
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607D]
-ParameterName=software_position_limit
-ObjectType=0x8
-SubNumber=3
-
-[607Dsub0]
-ParameterName=software_position_limit_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[607Dsub1]
-ParameterName=software_position_limit_min
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=-900000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607Dsub2]
-ParameterName=software_position_limit_max
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=900000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[607E]
-ParameterName=polarity
-ObjectType=0x7
-DataType=0x0005
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=255
-
-[607F]
-ParameterName=max_profile_velocity
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=2000000000
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6080]
-ParameterName=max_motor_speed
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0xFFFFFFFF
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6081]
-ParameterName=profile_velocity
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=2000000000
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6082]
-ParameterName=end_velocity
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6083]
-ParameterName=profile_acceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=2000000000
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6084]
-ParameterName=profile_deceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=2000000000
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6085]
-ParameterName=quick_stop_deceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=2000000000
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6086]
-ParameterName=motion_profile_type
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-32768
-HighLimit=0
-
-[6087]
-ParameterName=torque_slope
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=10000000
-PDOMapping=1
-LowLimit=0
-HighLimit=10000000
-
-[608C]
-ParameterName=Velocity Dimension Index
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[608E]
-ParameterName=Acceleration Dimension Index
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[608F]
-ParameterName=position_encoder_resolution
-ObjectType=0x8
-SubNumber=3
-
-[608Fsub0]
-ParameterName=position_encoder_resolution_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-LowLimit=2
-HighLimit=2
-
-[608Fsub1]
-ParameterName=encoder_increments
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[608Fsub2]
-ParameterName=motor_revolutions
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6090]
-ParameterName=velocity_encoder_resolution
-ObjectType=0x8
-SubNumber=3
-
-[6090sub0]
-ParameterName=velocity_encoder_resolution_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-LowLimit=2
-HighLimit=2
-
-[6090sub1]
-ParameterName=encoder_increments_per_second
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6090sub2]
-ParameterName=motor_revolutions_per_second
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6091]
-ParameterName=gear_ratio
-ObjectType=0x8
-SubNumber=3
-
-[6091sub0]
-ParameterName=gear_ratio_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-LowLimit=0
-HighLimit=2
-
-[6091sub1]
-ParameterName=gear_ratio_motor_revolutions
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6091sub2]
-ParameterName=gear_ratio_shaft_revolutions
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6092]
-ParameterName=feed_constant
-ObjectType=0x8
-SubNumber=3
-
-[6092sub0]
-ParameterName=feed_constant_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[6092sub1]
-ParameterName=feed_constant_feed
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[6092sub2]
-ParameterName=feed_constant_shaft_revolutions
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=0xFFFFFFFF
-
-[6096]
-ParameterName=Velocity Factor
-ObjectType=0x8
-SubNumber=3
-
-[6096sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-
-[6096sub1]
-ParameterName=Velocity Factor_Numerator
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=0xFFFFFFFF
-
-[6096sub2]
-ParameterName=Velocity Factor_Divisor
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=0xFFFFFFFF
-
-[6097]
-ParameterName=Acceleration Factor
-ObjectType=0x8
-SubNumber=3
-
-[6097sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-
-[6097sub1]
-ParameterName=Acceleration Factor_sub1
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=0xFFFFFFFF
-
-[6097sub2]
-ParameterName=Acceleration Factor_sub2
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=0xFFFFFFFF
-
-[6098]
-ParameterName=homing_method
-ObjectType=0x7
-DataType=0x0002
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-128
-HighLimit=35
-ParameterValue=35
-
-[6099]
-ParameterName=homing_speeds
-ObjectType=0x8
-SubNumber=3
-
-[6099sub0]
-ParameterName=homing_speeds_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[6099sub1]
-ParameterName=homing_speeds_speed_during_search_for_switch
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-ParameterValue=100000
-HighLimit=0xFFFFFFFF
-
-[6099sub2]
-ParameterName=homing_speeds_speed_during_search_for_zero
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-ParameterValue=10000
-HighLimit=0xFFFFFFFF
-
-[609A]
-ParameterName=homing_acceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60B0]
-ParameterName=position_offset
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60B1]
-ParameterName=velocity_offset
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60B2]
-ParameterName=torque_offset
-ObjectType=0x7
-DataType=0x0003
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-32768
-HighLimit=32767
-
-[60B8]
-ParameterName=touch_probe_function
-ObjectType=0x7
-DataType=0x0006
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=65535
-
-[60B9]
-ParameterName=touch_probe_status
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=65535
-
-[60BA]
-ParameterName=touch_probe_1_pos_edge
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60BB]
-ParameterName=touch_probe_1_neg_edge
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60BC]
-ParameterName=touch_probe_2_pos_edge
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60BD]
-ParameterName=touch_probe_2_neg_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60C0]
-ParameterName=interpolation_sub_mode_select
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-1
-HighLimit=0
-
-[60C1]
-ParameterName=interpolation_data_record
-ObjectType=0x8
-SubNumber=3
-
-[60C1sub0]
-ParameterName=interpolation_data_record_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[60C1sub1]
-ParameterName=interpolation_data_record_setpoint_1
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60C1sub2]
-ParameterName=interpolation_data_record_setpoint_2
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60C2]
-ParameterName=interpolation_time_period
-ObjectType=0x9
-SubNumber=3
-
-[60C2sub0]
-ParameterName=interpolation_time_period_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[60C2sub1]
-ParameterName=interpolation_time_period_value
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=1
-ParameterValue=10
-PDOMapping=0
-LowLimit=1
-HighLimit=255
-
-[60C2sub2]
-ParameterName=interpolation_time_period_index
-ObjectType=0x7
-DataType=0x0002
-AccessType=rw
-DefaultValue=-3
-PDOMapping=0
-LowLimit=-6
-HighLimit=-2
-
-[60C4]
-ParameterName=interpolation_data_configuration
-ObjectType=0x9
-SubNumber=7
-
-[60C4sub0]
-ParameterName=interpolation_data_configuration_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=6
-PDOMapping=0
-LowLimit=6
-HighLimit=6
-
-[60C4sub1]
-ParameterName=interpolation_data_configuration_maximum_buffer_size
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=16
-
-[60C4sub2]
-ParameterName=interpolation_data_configuration_actual_buffer_size
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=16
-
-[60C4sub3]
-ParameterName=interpolation_data_configuration_buffer_organization
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[60C4sub4]
-ParameterName=interpolation_data_configuration_buffer_position
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=15
-
-[60C4sub5]
-ParameterName=interpolation_data_configuration_size_of_data_record
-ObjectType=0x7
-DataType=0x0005
-AccessType=rw
-DefaultValue=4
-PDOMapping=0
-LowLimit=4
-HighLimit=8
-
-[60C4sub6]
-ParameterName=interpolation_data_configuration_buffer_clear
-ObjectType=0x7
-DataType=0x0005
-AccessType=wo
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[60C5]
-ParameterName=max_acceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=2000000000
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60C6]
-ParameterName=max_deceleration
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=2000000000
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60E0]
-ParameterName=Positive Torque Limit Value
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=50000
-PDOMapping=0
-LowLimit=0
-HighLimit=50000
-
-[60E1]
-ParameterName=Negative Torque Limit Value
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=50000
-PDOMapping=0
-LowLimit=0
-HighLimit=50000
-
-[60E3]
-ParameterName=Supported Homing Methods
-ObjectType=0x8
-SubNumber=34
-
-[60E3sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=33
-PDOMapping=0
-
-[60E3sub1]
-ParameterName=Object 60E3_sub1
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub2]
-ParameterName=Object 60E3_sub2
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub3]
-ParameterName=Object 60E3_sub3
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub4]
-ParameterName=Object 60E3_sub4
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub5]
-ParameterName=Object 60E3_sub5
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub6]
-ParameterName=Object 60E3_sub6
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub7]
-ParameterName=Object 60E3_sub7
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub8]
-ParameterName=Object 60E3_sub8
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub9]
-ParameterName=Object 60E3_sub9
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subA]
-ParameterName=Object 60E3_subA
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subB]
-ParameterName=Object 60E3_subB
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subC]
-ParameterName=Object 60E3_subC
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subD]
-ParameterName=Object 60E3_subD
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subE]
-ParameterName=Object 60E3_subE
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3subF]
-ParameterName=Object 60E3_subF
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub10]
-ParameterName=Object 60E3_sub10
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub11]
-ParameterName=Object 60E3_sub11
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub12]
-ParameterName=Object 60E3_sub12
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub13]
-ParameterName=Object 60E3_sub13
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub14]
-ParameterName=Object 60E3_sub14
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub15]
-ParameterName=Object 60E3_sub15
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub16]
-ParameterName=Object 60E3_sub16
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub17]
-ParameterName=Object 60E3_sub17
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub18]
-ParameterName=Object 60E3_sub18
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub19]
-ParameterName=Object 60E3_sub19
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1A]
-ParameterName=Object 60E3_sub1A
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1B]
-ParameterName=Object 60E3_sub1B
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1C]
-ParameterName=Object 60E3_sub1C
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1D]
-ParameterName=Object 60E3_sub1D
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1E]
-ParameterName=Object 60E3_sub1E
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub1F]
-ParameterName=Object 60E3_sub1F
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub20]
-ParameterName=Object 60E3_sub20
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E3sub21]
-ParameterName=Object 60E3_sub21
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=0
-
-[60E4]
-ParameterName=Additional Position Actual Value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60E5]
-ParameterName=Additional Velocity Actual Value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60F2]
-ParameterName=positioning_option_code
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-PDOMapping=0
-
-[60F4]
-ParameterName=following_error_actual_value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60FA]
-ParameterName=Control Effort
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60FC]
-ParameterName=Position Demand Internal Value
-ObjectType=0x7
-DataType=0x0004
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[60FD]
-ParameterName=digital_inputs
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60FE]
-ParameterName=digital_outputs
-ObjectType=0x8
-SubNumber=3
-
-[60FEsub0]
-ParameterName=digital_outputs_highest_subindex
-ObjectType=0x7
-DataType=0x0005
-AccessType=const
-DefaultValue=2
-PDOMapping=0
-
-[60FEsub1]
-ParameterName=digital_outputs_physical_outputs
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60FEsub2]
-ParameterName=digital_outputs_bit_mask
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[60FF]
-ParameterName=target_velocity
-ObjectType=0x7
-DataType=0x0004
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[6502]
-ParameterName=supported_drive_modes
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=0
-
-[ManufacturerObjects]
-SupportedObjects=44
-1=0x2005
-2=0x2012
-3=0x2013
-4=0x2020
-5=0x2030
-6=0x2035
-7=0x2036
-8=0x2041
-9=0x2045
-10=0x2051
-11=0x2060
-12=0x207B
-13=0x2081
-14=0x2082
-15=0x2085
-16=0x2086
-17=0x2087
-18=0x2090
-19=0x20A0
-20=0x20B0
-21=0x20FC
-22=0x20FD
-23=0x2201
-24=0x2202
-25=0x2203
-26=0x2205
-27=0x2206
-28=0x22A0
-29=0x22A1
-30=0x22A2
-31=0x22A3
-32=0x2E06
-33=0x2E07
-34=0x2E10
-35=0x2E15
-36=0x2F00
-37=0x2F01
-38=0x2F05
-39=0x2F20
-40=0x2F21
-41=0x2F41
-42=0x2F45
-43=0x2F70
-44=0x2F75
-
-[2005]
-ParameterName=Fast Reference
-ObjectType=0x7
-DataType=0x0004
-AccessType=rwr
-PDOMapping=1
-
-[2012]
-ParameterName=Binary Interpreter Input
-ObjectType=0x7
-DataType=0x001b
-AccessType=wo
-PDOMapping=1
-
-[2013]
-ParameterName=Binary Interpreter Output
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=1
-
-[2020]
-ParameterName=Home Block Limit Parameters
-ObjectType=0x9
-SubNumber=6
-
-[2020sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=5
-PDOMapping=0
-
-[2020sub1]
-ParameterName=Torque Limit
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2020sub2]
-ParameterName=Time Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2020sub3]
-ParameterName=Distance Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2020sub4]
-ParameterName=Detection Velocity Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2020sub5]
-ParameterName=Detection Velocity Time Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2030]
-ParameterName=Upload Recording Data
-ObjectType=0x9
-SubNumber=17
-
-[2030sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=16
-PDOMapping=0
-
-[2030sub1]
-ParameterName=Main Speed
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub2]
-ParameterName=Main Position
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub3]
-ParameterName=Position Command
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub4]
-ParameterName=Digital Input
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub5]
-ParameterName=Position Error
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub6]
-ParameterName=Torque Command
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub7]
-ParameterName=Bus Voltage
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub8]
-ParameterName=Velocity Command
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub9]
-ParameterName=Field Angle
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subA]
-ParameterName=Active Current
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subB]
-ParameterName=Reactive Current
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subC]
-ParameterName=Analog Input 1
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subD]
-ParameterName=Analog Input 2
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subE]
-ParameterName=Current Phase A
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030subF]
-ParameterName=Current Phase B
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2030sub10]
-ParameterName=Current Phase C
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2035]
-ParameterName=Upload Data Parameters
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[2036]
-ParameterName=Upload Data
-ObjectType=0x7
-DataType=0x001b
-AccessType=ro
-PDOMapping=0
-
-[2041]
-ParameterName=Timestamp
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=1
-
-[2045]
-ParameterName=Block upload inhibit time parameter
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2051]
-ParameterName=Download Data
-ObjectType=0x7
-DataType=0x001b
-AccessType=wo
-PDOMapping=0
-
-[2060]
-ParameterName=Drive Parameters Checksum
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[207B]
-ParameterName=Additional Position Range Limit
-ObjectType=0x8
-SubNumber=3
-
-[207Bsub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-
-[207Bsub1]
-ParameterName=Min additional position range limit
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=-1000000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[207Bsub2]
-ParameterName=Max additional position range limit
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=1000000000
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2081]
-ParameterName=Extended Error Code
-ObjectType=0x8
-SubNumber=7
-
-[2081sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=6
-PDOMapping=0
-
-[2081sub1]
-ParameterName=Feedback Error
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2081sub2]
-ParameterName=Profile Initialization Error
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2081sub3]
-ParameterName=Download Procedure Error
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2081sub4]
-ParameterName=Elmo Error Code of SDO abort
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2081sub5]
-ParameterName=Motor Fault Reason
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2081sub6]
-ParameterName=ECAM Initialization Error
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2082]
-ParameterName=CAN Controller Status
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-
-[2085]
-ParameterName=Extra Status Register
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-PDOMapping=1
-
-[2086]
-ParameterName=STO Status Register
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[2087]
-ParameterName=PAL Version
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2090]
-ParameterName=Firmware Download
-ObjectType=0x7
-DataType=0x0007
-AccessType=wo
-PDOMapping=0
-
-[20A0]
-ParameterName=Auxilary Position Actual Value
-ObjectType=0x7
-DataType=0x0004
-AccessType=rwr
-DefaultValue=0
-PDOMapping=1
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[20B0]
-ParameterName=Socket Additional Function
-ObjectType=0x8
-SubNumber=10
-
-[20B0sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=9
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[20B0sub1]
-ParameterName=Position Loop Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub2]
-ParameterName=Velocity Loop Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub3]
-ParameterName=Commutation Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub4]
-ParameterName=Position Reference Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub5]
-ParameterName=Velocity Reference Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub6]
-ParameterName=Current Reference Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub7]
-ParameterName=Touch Probe Capturing Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub8]
-ParameterName=Homing Reference Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20B0sub9]
-ParameterName=Additional Sensor Readout Socket
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=0
-HighLimit=4294967295
-
-[20FC]
-ParameterName=Absolute Sensor Function
-ObjectType=0x8
-SubNumber=3
-
-[20FCsub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[20FCsub1]
-ParameterName=Reset Multiturn
-ObjectType=0x7
-DataType=0x0006
-AccessType=wo
-PDOMapping=0
-
-[20FCsub2]
-ParameterName=Reset Endat Error
-ObjectType=0x7
-DataType=0x0006
-AccessType=wo
-PDOMapping=0
-
-[20FD]
-ParameterName=Digital Inputs
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-
-[2201]
-ParameterName=Digital Input Low Byte
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-PDOMapping=1
-
-[2202]
-ParameterName=Extended Input
-ObjectType=0x8
-SubNumber=4
-
-[2202sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=3
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2202sub1]
-ParameterName=Extended Input Value Bits 0_31
-ObjectType=0x7
-DataType=0x0007
-AccessType=rwr
-PDOMapping=1
-
-[2202sub2]
-ParameterName=Logic and Polarity
-ObjectType=0x7
-DataType=0x0007
-AccessType=rwr
-DefaultValue=0xFFFFFFFF
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2202sub3]
-ParameterName=PDO Event Mask
-ObjectType=0x7
-DataType=0x0007
-AccessType=rwr
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2203]
-ParameterName=Application Object
-ObjectType=0x7
-DataType=0x0007
-AccessType=ro
-PDOMapping=1
-
-[2205]
-ParameterName=Analog Input Object
-ObjectType=0x8
-SubNumber=3
-
-[2205sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-
-[2205sub1]
-ParameterName=Analog Input 1
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-PDOMapping=1
-LowLimit=-10000
-HighLimit=10000
-
-[2205sub2]
-ParameterName=Analog Input 2
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-PDOMapping=1
-LowLimit=-10000
-HighLimit=10000
-
-[2206]
-ParameterName=5V DC Supply
-ObjectType=0x7
-DataType=0x0003
-AccessType=ro
-PDOMapping=1
-
-[22A0]
-ParameterName=Digital Outputs
-ObjectType=0x7
-DataType=0x0005
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=255
-
-[22A1]
-ParameterName=Extended Outputs
-ObjectType=0x8
-SubNumber=4
-
-[22A1sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=3
-PDOMapping=0
-
-[22A1sub1]
-ParameterName=Extended Output bits 0_31
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[22A1sub2]
-ParameterName=Logic and Polarity
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0xFFFFFFFF
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[22A1sub3]
-ParameterName=Extended Outputs Mask
-ObjectType=0x7
-DataType=0x0007
-AccessType=rww
-DefaultValue=0xFFFFFFFF
-PDOMapping=1
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[22A2]
-ParameterName=Drive Temperature in C
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=1
-LowLimit=0
-HighLimit=65535
-
-[22A3]
-ParameterName=Temperature Array
-ObjectType=0x8
-SubNumber=4
-
-[22A3sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=3
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[22A3sub1]
-ParameterName=Drive Temperature in C
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-PDOMapping=0
-
-[22A3sub2]
-ParameterName=Drive Temperature in F
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-PDOMapping=0
-
-[22A3sub3]
-ParameterName=Encoder Temperature in C
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-PDOMapping=0
-
-[2E06]
-ParameterName=Torque Window
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=40
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[2E07]
-ParameterName=Torque Window Time
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=20
-PDOMapping=0
-LowLimit=0
-HighLimit=65535
-
-[2E10]
-ParameterName=Set Home Position Touch Probe
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=1
-
-[2E15]
-ParameterName=Gantry Yaw Offset
-ObjectType=0x7
-DataType=0x0003
-AccessType=rw
-PDOMapping=0
-
-[2F00]
-ParameterName=User Integer Array
-ObjectType=0x8
-SubNumber=25
-
-[2F00sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=24
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2F00sub1]
-ParameterName=User Integer_sub1
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub2]
-ParameterName=User Integer_sub2
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub3]
-ParameterName=User Integer_sub3
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub4]
-ParameterName=User Integer_sub4
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub5]
-ParameterName=User Integer_sub5
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub6]
-ParameterName=User Integer_sub6
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub7]
-ParameterName=User Integer_sub7
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub8]
-ParameterName=User Integer_sub8
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub9]
-ParameterName=User Integer_sub9
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subA]
-ParameterName=User Integer_subA
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subB]
-ParameterName=User Integer_subB
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subC]
-ParameterName=User Integer_subC
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subD]
-ParameterName=User Integer_subD
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subE]
-ParameterName=User Integer_subE
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00subF]
-ParameterName=User Integer_subF
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub10]
-ParameterName=User Integer_sub10
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub11]
-ParameterName=User Integer_sub11
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub12]
-ParameterName=User Integer_sub12
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub13]
-ParameterName=User Integer_sub13
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub14]
-ParameterName=User Integer_sub14
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub15]
-ParameterName=User Integer_sub15
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub16]
-ParameterName=User Integer_sub16
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub17]
-ParameterName=User Integer_sub17
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F00sub18]
-ParameterName=User Integer_sub18
-ObjectType=0x7
-DataType=0x0004
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=-2147483648
-HighLimit=2147483647
-
-[2F01]
-ParameterName=User Float Array
-ObjectType=0x8
-SubNumber=25
-
-[2F01sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=24
-PDOMapping=0
-
-[2F01sub1]
-ParameterName=User Float Array_sub1
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub2]
-ParameterName=User Float Array_sub2
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub3]
-ParameterName=User Float Array_sub3
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub4]
-ParameterName=User Float Array_sub4
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub5]
-ParameterName=User Float Array_sub5
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub6]
-ParameterName=User Float Array_sub6
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub7]
-ParameterName=User Float Array_sub7
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub8]
-ParameterName=User Float Array_sub8
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub9]
-ParameterName=User Float Array_sub9
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subA]
-ParameterName=User Float Array_subA
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subB]
-ParameterName=User Float Array_subB
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subC]
-ParameterName=User Float Array_subC
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subD]
-ParameterName=User Float Array_subD
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subE]
-ParameterName=User Float Array_subE
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01subF]
-ParameterName=User Float Array_subF
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub10]
-ParameterName=User Float Array_sub10
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub11]
-ParameterName=User Float Array_sub11
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub12]
-ParameterName=User Float Array_sub12
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub13]
-ParameterName=User Float Array_sub13
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub14]
-ParameterName=User Float Array_sub14
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub15]
-ParameterName=User Float Array_sub15
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub16]
-ParameterName=User Float Array_sub16
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub17]
-ParameterName=User Float Array_sub17
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F01sub18]
-ParameterName=User Float Array_sub18
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F05]
-ParameterName=Get Drive Control Board Type
-ObjectType=0x7
-DataType=0x0006
-AccessType=ro
-DefaultValue=0
-PDOMapping=0
-
-[2F20]
-ParameterName=TPDO asynchronous events
-ObjectType=0x8
-SubNumber=5
-
-[2F20sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=4
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2F20sub1]
-ParameterName=PDO1 trigger events
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x08000000
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F20sub2]
-ParameterName=PDO2 trigger events
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0x80000000
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F20sub3]
-ParameterName=PDO3 trigger events
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F20sub4]
-ParameterName=PDO4 trigger events
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F21]
-ParameterName=Emergency Events
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=0x7FF
-PDOMapping=0
-
-[2F41]
-ParameterName=DS402 Configuration Object
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-
-[2F45]
-ParameterName=Threshold Parameter
-ObjectType=0x8
-SubNumber=5
-
-[2F45sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=4
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2F45sub1]
-ParameterName=Under voltage threshold in mV
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F45sub2]
-ParameterName=Over voltage threshold in mV
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F45sub3]
-ParameterName=Analog Encoder Amplitude Threshold
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F45sub4]
-ParameterName=Over temperature Threshold in Celsius
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=85
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F70]
-ParameterName=Can Encoder Range
-ObjectType=0x8
-SubNumber=3
-
-[2F70sub0]
-ParameterName=NrOfObjects
-ObjectType=0x7
-DataType=0x0005
-AccessType=ro
-DefaultValue=2
-PDOMapping=0
-LowLimit=0
-HighLimit=255
-
-[2F70sub1]
-ParameterName=Low Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0
-PDOMapping=0
-LowLimit=0
-HighLimit=0
-
-[2F70sub2]
-ParameterName=High Limit
-ObjectType=0x7
-DataType=0x0007
-AccessType=rw
-DefaultValue=0xFFFFFFFF
-PDOMapping=0
-LowLimit=0
-HighLimit=0xFFFFFFFF
-
-[2F75]
-ParameterName=Extrapolation Cycles Timeout
-ObjectType=0x7
-DataType=0x0006
-AccessType=rw
-DefaultValue=1
-PDOMapping=0
-LowLimit=1
-HighLimit=32767
-
-[PreDefines]
-csp=
-cst=
-csv=
-hm=1
-ip=1
-pc=
-pp=1
-pv=1
-tq=1
-vl=
-
diff --git a/cob_hardware_config/cob4-4/config/Elmo.dcf b/cob_hardware_config/cob4-4/config/Elmo.dcf
new file mode 120000
index 000000000..478208c66
--- /dev/null
+++ b/cob_hardware_config/cob4-4/config/Elmo.dcf
@@ -0,0 +1 @@
+../../common/Elmo.dcf
\ No newline at end of file
diff --git a/cob_hardware_config/cob4-4/config/base_driver.yaml b/cob_hardware_config/cob4-4/config/base_driver.yaml
index 8a104c213..6ebc0e8fa 100644
--- a/cob_hardware_config/cob4-4/config/base_driver.yaml
+++ b/cob_hardware_config/cob4-4/config/base_driver.yaml
@@ -6,6 +6,14 @@ defaults:
"6084": "1000000"
"60C5": "1000000"
"60C6": "1000000"
+ "6099sub1": "100000" # find switch (coarse)
+ "6099sub2": "10000" # find home (fine)
+ "1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127
+
+drive_wheel: &drive_wheel
+ dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
+ "6098": "35" # homing method
+ vel_from_device: "p1 == nan || obj2041 == t1 ? 0 : deg2rad(1000*norm(obj6064-p1,-36000000,36000000)/norm(obj2041-t1,0,2^32)), p1=p0, p0 = obj6064, t1 = t0, t0 = obj2041"
nodes:
##Wheel 1
@@ -13,31 +21,28 @@ nodes:
id: 1
dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
"6098": "19" # homing method
- "607C": "-54359" # home offset
+ "607C": "-52047" # home offset
fl_caster_r_wheel_joint:
+ <<: *drive_wheel
id: 2
- dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
- "6098": "35" # homing method
##Wheel 2
b_caster_rotation_joint:
id: 3
dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
"6098": "19" # homing method
- "607C": "-175428" # home offset
+ "607C": "-172226" # home offset
b_caster_r_wheel_joint:
+ <<: *drive_wheel
id: 4
- dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
- "6098": "35" # homing method
##Wheel 3
fr_caster_rotation_joint:
id: 5
dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
"6098": "19" # homing method
- "607C": "-111597" # home offset
+ "607C": "67092" # home offset
fr_caster_r_wheel_joint:
+ <<: *drive_wheel
id: 6
- dcf_overlay: # "ObjectID" : "ParameterValue" (both as strings)
- "6098": "35" # homing method
diff --git a/cob_hardware_config/cob4-4/config/can0.yaml b/cob_hardware_config/cob4-4/config/can0.yaml
index 1504071be..50e990f30 100644
--- a/cob_hardware_config/cob4-4/config/can0.yaml
+++ b/cob_hardware_config/cob4-4/config/can0.yaml
@@ -1,5 +1,9 @@
bus:
device: can0
+ master_allocator: canopen::SimpleMaster::Allocator
sync:
- interval_ms: 10
+ interval_ms: 20
overflow: 0
+heartbeat:
+ rate: 20
+ msg: "77f#05"
diff --git a/cob_hardware_config/cob4-6/cob4-6.rviz b/cob_hardware_config/cob4-6/cob4-6.rviz
new file mode 120000
index 000000000..565746e47
--- /dev/null
+++ b/cob_hardware_config/cob4-6/cob4-6.rviz
@@ -0,0 +1 @@
+../common/cob4_base.rviz
\ No newline at end of file
diff --git a/cob_hardware_config/common/Elmo.dcf b/cob_hardware_config/common/Elmo.dcf
index e9ec1ea28..77d314819 100644
--- a/cob_hardware_config/common/Elmo.dcf
+++ b/cob_hardware_config/common/Elmo.dcf
@@ -1300,7 +1300,7 @@ AccessType=rw
PDOMapping=0
LowLimit=0
HighLimit=8
-ParameterValue=2
+ParameterValue=3
[1A00sub1]
ParameterName=Status Word
@@ -1327,6 +1327,7 @@ ObjectType=0x7
DataType=0x0007
AccessType=rw
PDOMapping=0
+ParameterValue=0x20410020
[1A00sub4]
ParameterName=PDO Mapping Entry_4
diff --git a/cob_hardware_config/common/cob4_base.rviz b/cob_hardware_config/common/cob4_base.rviz
new file mode 100644
index 000000000..c1c5b8c6d
--- /dev/null
+++ b/cob_hardware_config/common/cob4_base.rviz
@@ -0,0 +1,359 @@
+Panels:
+ - Class: rviz/Displays
+ Help Height: 78
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /Global Options1
+ Splitter Ratio: 0.622896
+ Tree Height: 785
+ - Class: rviz/Selection
+ Name: Selection
+ - Class: rviz/Tool Properties
+ Expanded:
+ - /2D Pose Estimate1
+ - /2D Nav Goal1
+ Name: Tool Properties
+ Splitter Ratio: 0.588679
+ - Class: rviz/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+ - Class: rviz/Time
+ Experimental: false
+ Name: Time
+ SyncMode: 0
+ SyncSource: LaserScan Left
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Class: rviz/Axes
+ Enabled: true
+ Length: 1
+ Name: Axes base_link
+ Radius: 0.1
+ Reference Frame: base_link
+ Value: true
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.03
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame:
+ Value: true
+ - Alpha: 1
+ Class: rviz/RobotModel
+ Collision Enabled: false
+ Enabled: true
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ b_caster_r_wheel_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ b_caster_rotation_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ base_footprint:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ base_laser_front_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ base_laser_left_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ base_laser_right_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ fl_caster_r_wheel_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ fl_caster_rotation_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ fr_caster_r_wheel_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ fr_caster_rotation_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ Name: RobotModel
+ Robot Description: robot_description
+ TF Prefix: ""
+ Update Interval: 0
+ Value: true
+ Visual Enabled: true
+ - Alpha: 1
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: x
+ Class: rviz/LaserScan
+ Color: 0; 255; 0
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 0; 255; 0
+ Max Intensity: 10.454
+ Min Color: 0; 255; 0
+ Min Intensity: 0.227896
+ Name: LaserScan Front
+ Position Transformer: XYZ
+ Queue Size: 10
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 0.025
+ Style: Spheres
+ Topic: /scan_front
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Alpha: 1
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz/LaserScan
+ Color: 0; 255; 0
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 0
+ Min Color: 0; 255; 0
+ Min Intensity: 0
+ Name: LaserScan Left
+ Position Transformer: XYZ
+ Queue Size: 10
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 0.025
+ Style: Spheres
+ Topic: /scan_left
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Alpha: 1
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz/LaserScan
+ Color: 0; 255; 0
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 4096
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: LaserScan Right
+ Position Transformer: XYZ
+ Queue Size: 10
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 0.025
+ Style: Spheres
+ Topic: /scan_right
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Class: rviz/MarkerArray
+ Enabled: true
+ Marker Topic: /safety_controller/marker
+ Name: Safety
+ Namespaces:
+ {}
+ Queue Size: 100
+ Value: true
+ - Arrow Length: 0.3
+ Class: rviz/PoseArray
+ Color: 255; 25; 0
+ Enabled: false
+ Name: PoseArray
+ Topic: /particlecloud
+ Value: false
+ - Class: rviz/TF
+ Enabled: false
+ Frame Timeout: 15
+ Frames:
+ All Enabled: false
+ Marker Scale: 1
+ Name: TF
+ Show Arrows: true
+ Show Axes: true
+ Show Names: true
+ Tree:
+ {}
+ Update Interval: 0
+ Value: false
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 0; 255; 0
+ Enabled: false
+ Name: Path dwa global
+ Topic: /move_base/DWAPlannerROS/global_plan
+ Value: false
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 0; 0; 255
+ Enabled: false
+ Name: Path dwa local
+ Topic: /move_base/DWAPlannerROS/local_plan
+ Value: false
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 0; 255; 0
+ Enabled: false
+ Name: Path tr global
+ Topic: /move_base/TrajectoryPlannerROS/global_plan
+ Value: false
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 0; 0; 255
+ Enabled: false
+ Name: Path tr local
+ Topic: /move_base/TrajectoryPlannerROS/local_plan
+ Value: false
+ - Class: rviz/InteractiveMarkers
+ Enable Transparency: true
+ Enabled: false
+ Name: InteractiveTeleop
+ Show Axes: false
+ Show Descriptions: true
+ Show Visual Aids: false
+ Update Topic: /cob_interactive_teleop/update
+ Value: false
+ - Alpha: 0.7
+ Class: rviz/Map
+ Color Scheme: map
+ Draw Behind: false
+ Enabled: false
+ Name: Map
+ Topic: /map
+ Value: false
+ - Alpha: 1
+ Class: rviz/GridCells
+ Color: 255; 0; 0
+ Enabled: false
+ Name: Obstacles
+ Topic: /move_base/local_costmap/obstacles
+ Value: false
+ - Alpha: 1
+ Class: rviz/GridCells
+ Color: 0; 0; 255
+ Enabled: false
+ Name: Inflated Obstacles
+ Topic: /move_base/local_costmap/inflated_obstacles
+ Value: false
+ Enabled: true
+ Global Options:
+ Background Color: 48; 48; 48
+ Fixed Frame: base_link
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz/Interact
+ Hide Inactive Objects: true
+ - Class: rviz/MoveCamera
+ - Class: rviz/Select
+ - Class: rviz/Measure
+ - Class: rviz/SetInitialPose
+ Topic: /initialpose
+ - Class: rviz/SetGoal
+ Topic: /move_base_simple/goal
+ Value: true
+ Views:
+ Current:
+ Class: rviz/Orbit
+ Distance: 16.8952
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.06
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Focal Point:
+ X: -0.408188
+ Y: -0.0225992
+ Z: -0.23833
+ Name: Current View
+ Near Clip Distance: 0.01
+ Pitch: 1.2698
+ Target Frame:
+ Value: Orbit (rviz)
+ Yaw: 6.0113
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Height: 998
+ Hide Left Dock: false
+ Hide Right Dock: false
+ QMainWindow State: 000000ff00000000fd00000004000000000000012b000003a0fc0200000006fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003a0000000dd00fffffffb0000000c00430061006d00650072006100000002a5000000cd00000000000000000000000100000169000003bcfc0200000006fb000000140049006d00610067006500200044006f0077006e00000000280000014e0000000000000000fb000000140049006d0061006700650020004c0065006600740000000028000001db0000000000000000fb000000160049006d0061006700650020005200690067006800740000000028000003bc0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000326000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000052e000003a000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Selection:
+ collapsed: false
+ Time:
+ collapsed: false
+ Tool Properties:
+ collapsed: false
+ Views:
+ collapsed: false
+ Width: 1631
+ X: 1721
+ Y: 26
diff --git a/cob_hardware_config/raw3-1/config/teleop.yaml b/cob_hardware_config/raw3-1/config/teleop.yaml
index 2eeef032d..fb4fb8932 100644
--- a/cob_hardware_config/raw3-1/config/teleop.yaml
+++ b/cob_hardware_config/raw3-1/config/teleop.yaml
@@ -5,7 +5,7 @@ run_factor: 2.0
joy_num_buttons: 12
joy_num_axes: 6
joy_num_modes: 1
-light_topic_name: /light
+light_action_name: /light/set_light
# axes
axis_vx: 1
diff --git a/cob_hardware_config/raw3-3/config/teleop.yaml b/cob_hardware_config/raw3-3/config/teleop.yaml
index 90ad19a5d..3e3880d15 100644
--- a/cob_hardware_config/raw3-3/config/teleop.yaml
+++ b/cob_hardware_config/raw3-3/config/teleop.yaml
@@ -5,7 +5,7 @@ run_factor: 2.0
joy_num_buttons: 12
joy_num_axes: 6
joy_num_modes: 1
-light_topic_name: /light
+light_action_name: /light/set_light
# axes
axis_vx: 1