|
| 1 | +'use strict'; |
| 2 | + |
| 3 | +let rosnodejs = require('./index.js'); |
| 4 | + |
| 5 | +rosnodejs.initNode('/my_node', { |
| 6 | + messages: [ |
| 7 | + 'rosgraph_msgs/Log', // required for new logging approach |
| 8 | + 'turtlesim/Pose', |
| 9 | + 'turtle_actionlib/ShapeActionGoal', |
| 10 | + 'geometry_msgs/Twist' |
| 11 | + ], |
| 12 | + services: ['std_srvs/SetBool', "turtlesim/TeleportRelative"] |
| 13 | + // actions: ['turtle_actionlib/Shape'] |
| 14 | +}).then((rosNode) => { |
| 15 | + |
| 16 | + // --------------------------------------------------------- |
| 17 | + // Service Call |
| 18 | + |
| 19 | + const TeleportRelative = rosnodejs.require('turtlesim').srv.TeleportRelative; |
| 20 | + console.log(TeleportRelative); |
| 21 | + const teleport_request = new TeleportRelative.Request({ |
| 22 | + linear: 0.1, |
| 23 | + angular: 0.0 |
| 24 | + }); |
| 25 | + |
| 26 | + let serviceClient2 = rosNode.serviceClient("/turtle1/teleport_relative", |
| 27 | + "turtlesim/TeleportRelative"); |
| 28 | + rosNode.waitForService(serviceClient2.getService(), 2000) |
| 29 | + .then((available) => { |
| 30 | + if (available) { |
| 31 | + serviceClient2.call(teleport_request, (resp) => { |
| 32 | + console.log('Service response ' + JSON.stringify(resp)); |
| 33 | + }); |
| 34 | + } else { |
| 35 | + console.log('Service not available'); |
| 36 | + } |
| 37 | + }); |
| 38 | + |
| 39 | + |
| 40 | + // --------------------------------------------------------- |
| 41 | + // Subscribe |
| 42 | + rosNode.subscribe( |
| 43 | + '/turtle1/pose', |
| 44 | + 'turtlesim/Pose', |
| 45 | + (data) => { |
| 46 | + console.log('pose', data); |
| 47 | + }, |
| 48 | + {queueSize: 1, |
| 49 | + throttleMs: 1000}); |
| 50 | + |
| 51 | + // --------------------------------------------------------- |
| 52 | + // Publish |
| 53 | + // equivalent to: |
| 54 | + // rostopic pub /turtle1/cmd_vel geometry_msgs/Twist '[1, 0, 0]' '[0, 0, 0]' |
| 55 | + // sudo tcpdump -ASs 0 -i lo | tee tmp/rostopic.dump |
| 56 | + let cmd_vel = rosNode.advertise('/turtle1/cmd_vel','geometry_msgs/Twist', { |
| 57 | + queueSize: 1, |
| 58 | + latching: true, |
| 59 | + throttleMs: 9 |
| 60 | + }); |
| 61 | + cmd_vel.on('registered', function() { |
| 62 | + console.log("registered"); |
| 63 | + const Twist = rosnodejs.require('geometry_msgs').msg.Twist; |
| 64 | + const msgTwist = new Twist(); |
| 65 | + msgTwist.linear = new (rosnodejs.require('geometry_msgs').msg.Vector3)(); |
| 66 | + msgTwist.linear.x = 1; |
| 67 | + msgTwist.linear.y = 0; |
| 68 | + msgTwist.linear.z = 0; |
| 69 | + msgTwist.angular = new (rosnodejs.require('geometry_msgs').msg.Vector3)(); |
| 70 | + msgTwist.angular.x = 0; |
| 71 | + msgTwist.angular.y = 0; |
| 72 | + msgTwist.angular.z = 0; |
| 73 | + console.log("Twist", msgTwist); |
| 74 | + cmd_vel.publish(msgTwist); |
| 75 | + }); |
| 76 | + cmd_vel.on('connection', function(s) { |
| 77 | + console.log("connected", s); |
| 78 | + }); |
| 79 | + |
| 80 | + |
| 81 | + // --------------------------------------------------------- |
| 82 | + // test actionlib |
| 83 | + // rosrun turtlesim turtlesim_node |
| 84 | + // rosrun turtle_actionlib shape_server |
| 85 | + |
| 86 | + let pub_action = |
| 87 | + rosNode.advertise('/turtle_shape/goal', 'turtle_actionlib/ShapeActionGoal', { |
| 88 | + queueSize: 1, |
| 89 | + latching: true, |
| 90 | + throttleMs: 9 |
| 91 | + }); |
| 92 | + |
| 93 | + let shapeActionGoal = rosnodejs.require('turtle_actionlib').msg.ShapeActionGoal; |
| 94 | + console.log("shapeMsgGoal", shapeActionGoal); |
| 95 | + let now = Date.now(); |
| 96 | + let secs = parseInt(now/1000); |
| 97 | + let nsecs = (now % 1000) * 1000; |
| 98 | + let shapeMsg = new shapeActionGoal({ |
| 99 | + header: { |
| 100 | + seq: 0, |
| 101 | + stamp: { |
| 102 | + secs: secs, |
| 103 | + nsecs: nsecs |
| 104 | + }, |
| 105 | + frame_id: '' |
| 106 | + }, |
| 107 | + goal_id: { |
| 108 | + stamp: { |
| 109 | + secs: secs, |
| 110 | + nsecs: nsecs |
| 111 | + }, |
| 112 | + id: "/my_node-1-"+secs+"."+nsecs+"000" |
| 113 | + }, |
| 114 | + goal: { |
| 115 | + edges: 5, |
| 116 | + radius: 1 |
| 117 | + } |
| 118 | + }); |
| 119 | + |
| 120 | + console.log("shapeMsg", shapeMsg); |
| 121 | + pub_action.publish(shapeMsg); |
| 122 | + |
| 123 | + console.log("\n** done\n"); |
| 124 | + |
| 125 | + |
| 126 | +}); |
0 commit comments