Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions examples/node_simple.js
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ var cmdVel = new ROSLIB.Topic({
messageType: 'geometry_msgs/Twist'
});

var twist = new ROSLIB.Message({
var twist = {
linear: {
x: 0.1,
y: 0.2,
Expand All @@ -39,7 +39,7 @@ angular: {
y: -0.2,
z: -0.3
}
});
};

console.log('Publishing cmd_vel');
cmdVel.publish(twist);
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,11 @@ function SendMessage() {
messageType: 'geometry_msgs/Pose2D'
})

const data = new ROSLIB.Message({
x: linear.x,
y: linear.y,
theta: angular.z
})
const data = {
x: linear.x,
y: linear.y,
theta: angular.z
}

// publishes to the queue
console.log('msg', data)
Expand Down
8 changes: 4 additions & 4 deletions examples/ros2_simple.html
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@

// Then we create the payload to be published. The object we pass in to ros.Message matches the
// fields defined in the geometry_msgs/Twist.msg definition.
var twist = new ROSLIB.Message({
var twist = {
linear : {
x : 0.1,
y : 0.2,
Expand All @@ -60,7 +60,7 @@
y : -0.2,
z : -0.3
}
});
};

// And finally, publish.
cmdVel.publish(twist);
Expand Down Expand Up @@ -96,10 +96,10 @@

// Then we create a Service Request. The object we pass in to ROSLIB.ServiceRequest matches the
// fields defined in the rospy_tutorials AddTwoInts.srv file.
var request = new ROSLIB.ServiceRequest({
var request = {
a : 1,
b : 2
});
};

// Finally, we call the /add_two_ints service and get back the results in the callback. The result
// is a ROSLIB.ServiceResponse object.
Expand Down
8 changes: 4 additions & 4 deletions examples/simple.html
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@

// Then we create the payload to be published. The object we pass in to ros.Message matches the
// fields defined in the geometry_msgs/Twist.msg definition.
var twist = new ROSLIB.Message({
var twist = {
linear : {
x : 0.1,
y : 0.2,
Expand All @@ -60,7 +60,7 @@
y : -0.2,
z : -0.3
}
});
};

// And finally, publish.
cmdVel.publish(twist);
Expand Down Expand Up @@ -96,10 +96,10 @@

// Then we create a Service Request. The object we pass in to ROSLIB.ServiceRequest matches the
// fields defined in the rospy_tutorials AddTwoInts.srv file.
var request = new ROSLIB.ServiceRequest({
var request = {
a : 1,
b : 2
});
};

// Finally, we call the /add_two_ints service and get back the results in the callback. The result
// is a ROSLIB.ServiceResponse object.
Expand Down
2 changes: 1 addition & 1 deletion src/actionlib/ActionClient.js
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ export default class ActionClient extends EventEmitter {
* Cancel all goals associated with this ActionClient.
*/
cancel() {
var cancelMessage = new Message();
var cancelMessage = {};
this.cancelTopic.publish(cancelMessage);
}
/**
Expand Down
8 changes: 4 additions & 4 deletions src/actionlib/Goal.js
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ export default class Goal extends EventEmitter {
// Create a random ID
this.goalID = 'goal_' + Math.random() + '_' + date.getTime();
// Fill in the goal message
this.goalMessage = new Message({
this.goalMessage = {
goal_id: {
stamp: {
secs: 0,
Expand All @@ -44,7 +44,7 @@ export default class Goal extends EventEmitter {
id: this.goalID
},
goal: this.goalMessage
});
};

this.on('status', function (status) {
that.status = status;
Expand Down Expand Up @@ -82,9 +82,9 @@ export default class Goal extends EventEmitter {
* Cancel the current goal.
*/
cancel() {
var cancelMessage = new Message({
var cancelMessage = {
id: this.goalID
});
};
this.actionClient.cancelTopic.publish(cancelMessage);
}
}
32 changes: 12 additions & 20 deletions src/actionlib/SimpleActionServer.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
*/

import Topic from '../core/Topic.js';
import Message from '../core/Message.js';
import Ros from '../core/Ros.js';
import { EventEmitter } from 'eventemitter3';

Expand Down Expand Up @@ -65,13 +64,14 @@ export default class SimpleActionServer extends EventEmitter {
});

// Track the goals and their status in order to publish status...
this.statusMessage = new Message({
this.statusMessage = {
header: {
stamp: { secs: 0, nsecs: 100 },
frame_id: ''
},
/** @type {{goal_id: any, status: number}[]} */
status_list: []
});
};

// needed for handling preemption prompted by a new goal being received
this.currentGoal = null; // currently tracked goal
Expand All @@ -83,10 +83,7 @@ export default class SimpleActionServer extends EventEmitter {
// needs to happen AFTER rest is set up
that.emit('cancel');
} else {
// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
that.statusMessage.status_list = [
{ goal_id: goalMessage.goal_id, status: 1 }
];
that.statusMessage.status_list = [{ goal_id: goalMessage.goal_id, status: 1 }];
that.currentGoal = goalMessage;
that.emit('goal', goalMessage.goal);
}
Expand Down Expand Up @@ -157,9 +154,7 @@ export default class SimpleActionServer extends EventEmitter {
var nsecs = Math.round(
1000000000 * (currentTime.getTime() / 1000 - secs)
);
// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
that.statusMessage.header.stamp.secs = secs;
// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
that.statusMessage.header.stamp.nsecs = nsecs;
statusPublisher.publish(that.statusMessage);
}, 500); // publish every 500ms
Expand All @@ -170,13 +165,12 @@ export default class SimpleActionServer extends EventEmitter {
* @param {Object} result - The result to return to the client.
*/
setSucceeded(result) {
var resultMessage = new Message({
var resultMessage = {
status: { goal_id: this.currentGoal.goal_id, status: 3 },
result: result
});
};
this.resultPublisher.publish(resultMessage);

// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
this.statusMessage.status_list = [];
if (this.nextGoal) {
this.currentGoal = this.nextGoal;
Expand All @@ -192,13 +186,12 @@ export default class SimpleActionServer extends EventEmitter {
* @param {Object} result - The result to return to the client.
*/
setAborted(result) {
var resultMessage = new Message({
var resultMessage = {
status: { goal_id: this.currentGoal.goal_id, status: 4 },
result: result
});
};
this.resultPublisher.publish(resultMessage);

// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
this.statusMessage.status_list = [];
if (this.nextGoal) {
this.currentGoal = this.nextGoal;
Expand All @@ -214,21 +207,20 @@ export default class SimpleActionServer extends EventEmitter {
* @param {Object} feedback - The feedback to send to the client.
*/
sendFeedback(feedback) {
var feedbackMessage = new Message({
var feedbackMessage = {
status: { goal_id: this.currentGoal.goal_id, status: 1 },
feedback: feedback
});
};
this.feedbackPublisher.publish(feedbackMessage);
}
/**
* Handle case where client requests preemption.
*/
setPreempted() {
// @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types.
this.statusMessage.status_list = [];
var resultMessage = new Message({
var resultMessage = {
status: { goal_id: this.currentGoal.goal_id, status: 2 }
});
};
this.resultPublisher.publish(resultMessage);

if (this.nextGoal) {
Expand Down
13 changes: 5 additions & 8 deletions src/core/Param.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
*/

import Service from './Service.js';
import ServiceRequest from './ServiceRequest.js';
import Ros from '../core/Ros.js';

/**
Expand Down Expand Up @@ -41,9 +40,7 @@ export default class Param {
serviceType: 'rosapi/GetParam'
});

var request = new ServiceRequest({
name: this.name
});
var request = {name: this.name};

paramClient.callService(
request,
Expand Down Expand Up @@ -76,10 +73,10 @@ export default class Param {
serviceType: 'rosapi/SetParam'
});

var request = new ServiceRequest({
var request = {
name: this.name,
value: JSON.stringify(value)
});
};

paramClient.callService(request, callback, failedCallback);
}
Expand All @@ -96,9 +93,9 @@ export default class Param {
serviceType: 'rosapi/DeleteParam'
});

var request = new ServiceRequest({
var request = {
name: this.name
});
};

paramClient.callService(request, callback, failedCallback);
}
Expand Down
Loading