Skip to content

ductility/open_manipulator_nodered_controller

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

21 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

OpenManipulator NODE-RED Controller

ROS package for controll OpenManipulator with Node-RED

Functions


Gripper Control, Sequential Control(ROUTIN buttons), specific pose button(INITIALPOSE, HOMEPOSE), Hand Guide Mode, Enable or Disable Actuator

Installation

This package works in the Ubuntu 16.04, ROS Kinetic, node.js v12.14.1, npm v6.13.4, Node-RED v1.0.3 .

  • Clone Robotis OpenManipulator packages and this repository at your catkin workspace.

If your catkin workspace is at ~/catkin_ws/, run the following command.

$ sudo apt-get install ros-kinetic-ros-controllers ros-kinetic-gazebo* ros-kinetic-moveit* ros-kinetic-industrial-core
$ cd ~/catkin_ws/src
$ git clone https://github.com/ROBOTIS-GIT/DynamixelSDK.git
$ git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench.git
$ git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench-msgs.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_msgs.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_simulations.git
$ git clone https://github.com/ROBOTIS-GIT/robotis_manipulator.git
$ git clone https://github.com/ductility/open_manipulator_nodered_controller.git

$ cd open_manipulator
$ git reset --hard 1228bd4e

$ cd ~/catkin_ws && catkin_make

The namespace has changed in the latest version of the Open manipulator. So use the software from the previous commit.

  • Install required Node-RED libraries.
$ cd ~/.node-red
$ npm install snappy-ros
$ npm install node-red-contrib-ros
$ npm install node-red-dashboard
[{"id":"f0730477.741638","type":"tab","label":"Controller","disabled":false,"info":""},{"id":"8e1a6ce3.bdaaf","type":"ros-server","z":"","url":"ws://localhost:9090"},{"id":"c8ff9173.adcae","type":"ros-server","z":"","url":"ws://localhost:9090"},{"id":"a972f19e.a9b75","type":"ui_base","theme":{"name":"theme-light","lightTheme":{"default":"#0094CE","baseColor":"#0094CE","baseFont":"-apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen-Sans,Ubuntu,Cantarell,Helvetica Neue,sans-serif","edited":true,"reset":false},"darkTheme":{"default":"#097479","baseColor":"#097479","baseFont":"-apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen-Sans,Ubuntu,Cantarell,Helvetica Neue,sans-serif","edited":false},"customTheme":{"name":"Untitled Theme 1","default":"#4B7930","baseColor":"#4B7930","baseFont":"-apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen-Sans,Ubuntu,Cantarell,Helvetica Neue,sans-serif"},"themeState":{"base-color":{"default":"#0094CE","value":"#0094CE","edited":false},"page-titlebar-backgroundColor":{"value":"#0094CE","edited":false},"page-backgroundColor":{"value":"#fafafa","edited":false},"page-sidebar-backgroundColor":{"value":"#ffffff","edited":false},"group-textColor":{"value":"#1bbfff","edited":false},"group-borderColor":{"value":"#ffffff","edited":false},"group-backgroundColor":{"value":"#ffffff","edited":false},"widget-textColor":{"value":"#111111","edited":false},"widget-backgroundColor":{"value":"#0094ce","edited":false},"widget-borderColor":{"value":"#ffffff","edited":false},"base-font":{"value":"-apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen-Sans,Ubuntu,Cantarell,Helvetica Neue,sans-serif"}},"angularTheme":{"primary":"indigo","accents":"blue","warn":"red","background":"grey"}},"site":{"name":"Node-RED Dashboard","hideToolbar":"false","allowSwipe":"false","lockMenu":"false","allowTempTheme":"true","dateFormat":"DD/MM/YYYY","sizes":{"sx":48,"sy":48,"gx":6,"gy":6,"cx":6,"cy":6,"px":0,"py":0}}},{"id":"3a62e8fe.6ab338","type":"ui_tab","z":"","name":"Controller","icon":"dashboard","order":1,"disabled":false,"hidden":false},{"id":"40d3d7c9.98c1b8","type":"ui_group","z":"","name":"Hand Guide","tab":"3a62e8fe.6ab338","order":1,"disp":true,"width":"6","collapse":false},{"id":"f3851a35.de7f68","type":"ui_group","z":"","name":"Buttons","tab":"3a62e8fe.6ab338","order":2,"disp":true,"width":"6","collapse":false},{"id":"920a2f08.bee05","type":"mqtt-broker","z":"","name":"","broker":"broker.mqtt-dashboard.com","port":"1883","clientid":"ysys","usetls":false,"compatmode":false,"keepalive":"60","cleansession":true,"birthTopic":"","birthQos":"0","birthPayload":"","closeTopic":"","closeQos":"0","closePayload":"","willTopic":"","willQos":"0","willPayload":""},{"id":"f7044120.18aab","type":"ros-subscriber","z":"f0730477.741638","topicname":"/open_manipulator/input_kinematics_pose","typepackage":"geometry_msgs","typename":"Pose","x":920,"y":920,"wires":[["13e1a3b.eab645c"]]},{"id":"eb4faf33.3767a","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/input_kinematics_pose","typepackage":"geometry_msgs","typename":"Pose","x":1080,"y":80,"wires":[]},{"id":"13e1a3b.eab645c","type":"debug","z":"f0730477.741638","name":"","active":false,"tosidebar":true,"console":false,"tostatus":false,"complete":"payload","targetType":"msg","x":1220,"y":920,"wires":[]},{"id":"b01e2eb5.2fbed","type":"function","z":"f0730477.741638","name":"Init_Pose","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.15,\n    \"y\": 0.0,\n    \"z\": 0.2\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":440,"y":60,"wires":[["eb4faf33.3767a"]]},{"id":"e848c72e.d33748","type":"function","z":"f0730477.741638","name":"Home_Pose","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.07,\n    \"y\": 0.0,\n    \"z\": 0.28\n  },\n  \"orientation\": {\n    \"x\": 0.01,\n    \"y\": -0.9,\n    \"z\": 0.006,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":450,"y":120,"wires":[["eb4faf33.3767a"]]},{"id":"4053bcdc.4a5b14","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":480,"y":240,"wires":[["82dc3829.2b2108"]]},{"id":"443bfbff.1ab424","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/input_gripper_angle","typepackage":"std_msgs","typename":"Float64","x":900,"y":600,"wires":[]},{"id":"b2f6ee7f.0923c","type":"ros-subscriber","z":"f0730477.741638","topicname":"/open_manipulator/input_gripper_angle","typepackage":"std_msgs","typename":"Float64","x":910,"y":980,"wires":[["f5e72007.053a4"]]},{"id":"f5e72007.053a4","type":"debug","z":"f0730477.741638","name":"","active":false,"tosidebar":true,"console":false,"tostatus":false,"complete":"false","x":1210,"y":980,"wires":[]},{"id":"25854e9f.1dee02","type":"function","z":"f0730477.741638","name":"Open(angle 0.01)","func":"var inputAngle = {\n  \"data\": 0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":290,"y":240,"wires":[["4053bcdc.4a5b14","443bfbff.1ab424"]]},{"id":"f96c8f8c.e588c","type":"function","z":"f0730477.741638","name":"object_position","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.25,\n    \"y\": 0.0,\n    \"z\": 0.04\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":660,"y":240,"wires":[[]]},{"id":"45fdc5e6.260c4c","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"2","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":860,"y":240,"wires":[["f1846f1.3b6209"]]},{"id":"f1846f1.3b6209","type":"function","z":"f0730477.741638","name":"Close(angle -0.01)","func":"var inputAngle = {\n  \"data\": -0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":1030,"y":240,"wires":[["443bfbff.1ab424","a01a9684.98d9f8"]]},{"id":"a01a9684.98d9f8","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":1240,"y":240,"wires":[["17a3de2d.2c9522"]]},{"id":"17a3de2d.2c9522","type":"function","z":"f0730477.741638","name":"up","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.2,\n    \"y\": 0.0,\n    \"z\": 0.25\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":150,"y":320,"wires":[["eb4faf33.3767a","78577f9a.aa25a"]]},{"id":"78577f9a.aa25a","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"3","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":300,"y":320,"wires":[["d9cc7e63.c65d3"]]},{"id":"d9cc7e63.c65d3","type":"function","z":"f0730477.741638","name":"down","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.2,\n    \"y\": -0.2,\n    \"z\": 0.05\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":470,"y":320,"wires":[["eb4faf33.3767a","24dfa3ce.efdacc"]]},{"id":"24dfa3ce.efdacc","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"2","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":640,"y":320,"wires":[["779ac990.c87e58"]]},{"id":"779ac990.c87e58","type":"function","z":"f0730477.741638","name":"Open(angle 0.01)","func":"var inputAngle = {\n  \"data\": 0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":830,"y":320,"wires":[["443bfbff.1ab424","155108b8.a476e7"]]},{"id":"5344baf4.2ee944","type":"function","z":"f0730477.741638","name":"Init_Pose","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.15,\n    \"y\": 0.0,\n    \"z\": 0.2\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":1240,"y":320,"wires":[["eb4faf33.3767a"]]},{"id":"155108b8.a476e7","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":1080,"y":320,"wires":[["5344baf4.2ee944"]]},{"id":"178e4cf6.70b7b3","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":480,"y":400,"wires":[["5faacf82.859f2"]]},{"id":"d6536729.0bfd78","type":"function","z":"f0730477.741638","name":"Open(angle 0.01)","func":"var inputAngle = {\n  \"data\": 0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":290,"y":400,"wires":[["178e4cf6.70b7b3","443bfbff.1ab424"]]},{"id":"1b4f8b32.45cf65","type":"function","z":"f0730477.741638","name":"object_position","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.25,\n    \"y\": 0.0,\n    \"z\": 0.04\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":460,"y":520,"wires":[[]]},{"id":"916578b9.627ed8","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"2","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":840,"y":400,"wires":[["e7574adb.14a178"]]},{"id":"e7574adb.14a178","type":"function","z":"f0730477.741638","name":"Close(angle -0.01)","func":"var inputAngle = {\n  \"data\": -0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":1030,"y":400,"wires":[["41a7ee5.4cd4c1","443bfbff.1ab424"]]},{"id":"41a7ee5.4cd4c1","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":1240,"y":400,"wires":[["21627c3.b4ae884"]]},{"id":"21627c3.b4ae884","type":"function","z":"f0730477.741638","name":"up","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.2,\n    \"y\": 0.0,\n    \"z\": 0.25\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":150,"y":480,"wires":[["9d4e0336.e7642","eb4faf33.3767a"]]},{"id":"9d4e0336.e7642","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"3","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":300,"y":480,"wires":[["e929d2ff.04a4d"]]},{"id":"5faacf82.859f2","type":"function","z":"f0730477.741638","name":"down","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.2,\n    \"y\": -0.2,\n    \"z\": 0.05\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":650,"y":400,"wires":[["916578b9.627ed8","eb4faf33.3767a"]]},{"id":"7c1dbd7e.760394","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"2","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":640,"y":480,"wires":[["54c4aeef.92d6f"]]},{"id":"54c4aeef.92d6f","type":"function","z":"f0730477.741638","name":"Open(angle 0.01)","func":"var inputAngle = {\n  \"data\": 0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":830,"y":480,"wires":[["24414558.4df1da","443bfbff.1ab424"]]},{"id":"db3cb5e7.f02758","type":"function","z":"f0730477.741638","name":"Init_Pose","func":"var inputPose = {\n  \"position\": {\n    \"x\": 0.15,\n    \"y\": 0.0,\n    \"z\": 0.2\n  },\n  \"orientation\": {\n    \"x\": 0,\n    \"y\": 0,\n    \"z\": 0,\n    \"w\": 1\n  }\n}\nmsg.payload = inputPose;\nreturn msg;\n\n\n","outputs":1,"noerr":0,"x":1240,"y":480,"wires":[["eb4faf33.3767a"]]},{"id":"24414558.4df1da","type":"delay","z":"f0730477.741638","name":"","pauseType":"delay","timeout":"1","timeoutUnits":"seconds","rate":"1","nbRateUnits":"1","rateUnits":"second","randomFirst":"1","randomLast":"5","randomUnits":"seconds","drop":false,"x":1080,"y":480,"wires":[["db3cb5e7.f02758"]]},{"id":"c004790e.43e048","type":"xml","z":"f0730477.741638","name":"my_world.world parser","property":"payload","attr":"","chr":"","x":560,"y":720,"wires":[["70b1ea48.4ae3a4","884c9253.11e6c"]]},{"id":"82dc3829.2b2108","type":"file in","z":"f0730477.741638","name":"my_world.world","filename":"/home/siop/catkin_ws/src/open_manipulator_simulations/open_manipulator_gazebo/worlds/my_world.world","format":"utf8","chunk":false,"sendError":false,"encoding":"utf8","x":320,"y":720,"wires":[["c004790e.43e048"]]},{"id":"70b1ea48.4ae3a4","type":"function","z":"f0730477.741638","name":"find model position","func":"var inputmsg = msg.payload.sdf.world[0].include[2].pose[0];\n\nvar modelPose = {\n    \"position\": {\n        \"x\": Number(inputmsg.split(' ')[0]),\n        \"y\": Number(inputmsg.split(' ')[1]),\n        \"z\": 0.04\n    },\n    \"orientation\": {\n        \"x\": 0,\n        \"y\": 0,\n        \"z\": 0,\n        \"w\": 1\n        \n    }\n}\n\nmsg.payload = modelPose;\nreturn msg;","outputs":1,"noerr":0,"x":830,"y":720,"wires":[["45fdc5e6.260c4c","eb4faf33.3767a"]]},{"id":"884c9253.11e6c","type":"debug","z":"f0730477.741638","name":"","active":false,"tosidebar":true,"console":false,"tostatus":false,"complete":"payload.sdf.world[0].include[2].pose[0]","targetType":"msg","x":930,"y":840,"wires":[]},{"id":"c688e945.42e898","type":"xml","z":"f0730477.741638","name":"my_world.world parser","property":"payload","attr":"","chr":"","x":560,"y":780,"wires":[["c4899dd6.8cd96"]]},{"id":"e929d2ff.04a4d","type":"file in","z":"f0730477.741638","name":"my_world.world","filename":"/home/siop/catkin_ws/src/open_manipulator_simulations/open_manipulator_gazebo/worlds/my_world.world","format":"utf8","chunk":false,"sendError":false,"encoding":"utf8","x":320,"y":780,"wires":[["c688e945.42e898"]]},{"id":"c4899dd6.8cd96","type":"function","z":"f0730477.741638","name":"find model position","func":"var inputmsg = msg.payload.sdf.world[0].include[2].pose[0];\n\nvar modelPose = {\n    \"position\": {\n        \"x\": Number(inputmsg.split(' ')[0]),\n        \"y\": Number(inputmsg.split(' ')[1]),\n        \"z\": 0.04\n    },\n    \"orientation\": {\n        \"x\": 0,\n        \"y\": 0,\n        \"z\": 0,\n        \"w\": 1\n        \n    }\n}\n\nmsg.payload = modelPose;\nreturn msg;","outputs":1,"noerr":0,"x":830,"y":780,"wires":[["7c1dbd7e.760394","eb4faf33.3767a"]]},{"id":"f70c05f9.404478","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":3,"width":"3","height":"1","passthru":false,"label":"InitialPose","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":190,"y":60,"wires":[["b01e2eb5.2fbed"]]},{"id":"d899aeae.891af","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":8,"width":"3","height":"1","passthru":false,"label":"HomePose","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":190,"y":120,"wires":[["e848c72e.d33748"]]},{"id":"b3d80c17.e6b77","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":9,"width":"3","height":"1","passthru":false,"label":"Routin1","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":120,"y":240,"wires":[["25854e9f.1dee02"]]},{"id":"129cfb1.8e2e305","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":10,"width":"3","height":"1","passthru":false,"label":"Routin2","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":110,"y":400,"wires":[["d6536729.0bfd78"]]},{"id":"c74775ba.bd4db8","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":1,"width":"3","height":"1","passthru":false,"label":"OPEN","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":150,"y":600,"wires":[["b9b16155.df73e"]]},{"id":"d43a8fc3.edb04","type":"ui_button","z":"f0730477.741638","name":"","group":"f3851a35.de7f68","order":2,"width":"3","height":"1","passthru":false,"label":"CLOSE","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"","payloadType":"str","topic":"","x":160,"y":640,"wires":[["1835ccec.63f353"]]},{"id":"b9b16155.df73e","type":"function","z":"f0730477.741638","name":"Open(angle 0.01)","func":"var inputAngle = {\n  \"data\": 0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":430,"y":580,"wires":[["443bfbff.1ab424"]]},{"id":"1835ccec.63f353","type":"function","z":"f0730477.741638","name":"Close(angle -0.01)","func":"var inputAngle = {\n  \"data\": -0.01\n}\nmsg.payload = inputAngle;\nreturn msg;","outputs":1,"noerr":0,"x":430,"y":640,"wires":[["443bfbff.1ab424"]]},{"id":"6c712bd8.953804","type":"ui_button","z":"f0730477.741638","name":"","group":"40d3d7c9.98c1b8","order":2,"width":"3","height":"1","passthru":false,"label":"start_stamp","tooltip":"","color":"","bgcolor":"#D96066","icon":"","payload":"true","payloadType":"bool","topic":"","x":170,"y":1160,"wires":[["9aeeb710.3a3d28"]]},{"id":"a1574b34.af84e8","type":"ui_button","z":"f0730477.741638","name":"","group":"40d3d7c9.98c1b8","order":3,"width":"3","height":"1","passthru":false,"label":"end_stamp","tooltip":"","color":"","bgcolor":"#D96066","icon":"","payload":"false","payloadType":"bool","topic":"","x":170,"y":1200,"wires":[["9aeeb710.3a3d28"]]},{"id":"2dc33b6a.2717c4","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/joint_angle_stamp","typepackage":"std_msgs","typename":"Bool","x":650,"y":1180,"wires":[]},{"id":"9aeeb710.3a3d28","type":"function","z":"f0730477.741638","name":"Start/End","func":"var inputStamp = {\n  \"data\": msg.payload\n}\nmsg.payload = inputStamp;\nreturn msg;","outputs":1,"noerr":0,"x":340,"y":1180,"wires":[["2dc33b6a.2717c4"]]},{"id":"3044ca31.84d656","type":"ui_button","z":"f0730477.741638","name":"","group":"40d3d7c9.98c1b8","order":4,"width":"6","height":"1","passthru":false,"label":"Move by Point","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"true","payloadType":"bool","topic":"","x":180,"y":1280,"wires":[["63bed5c8.f9ddfc"]]},{"id":"a9b5aeb.225e55","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/hand_guide_move_point","typepackage":"std_msgs","typename":"Bool","x":750,"y":1280,"wires":[]},{"id":"63bed5c8.f9ddfc","type":"function","z":"f0730477.741638","name":"Hand Guide move Point","func":"var inputStamp = {\n  \"data\": msg.payload\n}\nmsg.payload = inputStamp;\nreturn msg;","outputs":1,"noerr":0,"x":430,"y":1280,"wires":[["a9b5aeb.225e55"]]},{"id":"ae1acc44.59737","type":"ui_switch","z":"f0730477.741638","name":"","label":"ACTUATOR","tooltip":"","group":"40d3d7c9.98c1b8","order":1,"width":"6","height":"1","passthru":true,"decouple":"false","topic":"","style":"","onvalue":"true","onvalueType":"bool","onicon":"","oncolor":"","offvalue":"false","offvalueType":"bool","officon":"","offcolor":"","x":170,"y":1100,"wires":[["303c973a.9fdbb8"]]},{"id":"4bdf1e29.90f34","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/input_actuator_state","typepackage":"std_msgs","typename":"Bool","x":650,"y":1100,"wires":[]},{"id":"303c973a.9fdbb8","type":"function","z":"f0730477.741638","name":"Enable/Disable","func":"var inputActuatorState = {\n  \"data\": msg.payload\n}\nmsg.payload = inputActuatorState;\nreturn msg;","outputs":1,"noerr":0,"x":350,"y":1100,"wires":[["4bdf1e29.90f34"]]},{"id":"59d5ad21.539ee4","type":"ui_button","z":"f0730477.741638","name":"","group":"40d3d7c9.98c1b8","order":4,"width":"6","height":"1","passthru":false,"label":"Move by Path","tooltip":"","color":"","bgcolor":"#5FAAD9","icon":"","payload":"true","payloadType":"bool","topic":"","x":180,"y":1360,"wires":[["fb21637f.b3f45"]]},{"id":"1d2366fe.08c4d9","type":"ros-publisher","z":"f0730477.741638","topicname":"/open_manipulator/hand_guide_move_path","typepackage":"std_msgs","typename":"Bool","x":750,"y":1360,"wires":[]},{"id":"fb21637f.b3f45","type":"function","z":"f0730477.741638","name":"Hand Guide move Path","func":"var inputStamp = {\n  \"data\": msg.payload\n}\nmsg.payload = inputStamp;\nreturn msg;","outputs":1,"noerr":0,"x":430,"y":1360,"wires":[["1d2366fe.08c4d9"]]}]

Usage

  1. run node-red
$ node-red

Then terminal shows you ... [info] Server now running at http://127.0.0.1:1880/ ... (defalt port : 1880)

  1. Use your Internet browser to access the following address: http://localhost:1880/ui/

  2. Open several terminal windows to launch ROS launch files.

If you want to use real robot, use following codes. Before entering the code, the robot must be connected to the computer.

$ roscore
$ roslaunch open_manipulator_controller open_manipulator_controller.launch
$ roslaunch open_manipulator_nodered_controller open_manipulator_nodered_controller.launch

Else, if you want to use gazebo simulation, use following codes.

$ roscore
$ roslaunch open_manipulator_gazebo open_manipulator_gazebo.launch
$ roslaunch open_manipulator_controller open_manipulator_controller.launch use_platform:=false
$ roslaunch open_manipulator_nodered_controller open_manipulator_nodered_controller.launch
  1. Control with Node-RED dashboard!

To use Docker

https://github.com/ductility/om-nodered

About

ros package for controll open manipulator with node-red

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published