Secure your code as it's written. Use Snyk Code to scan source code in minutes - no build needed - and fix issues immediately.
tape('ROSBag#populated rosConfig results in empty topicMessageTypes ', async t => {
const config = new ROSConfig({
topicConfig: [
{
topic: '/foo',
type: 'foo_msg/Foo'
},
{
topic: '/bar',
type: 'bar_msg/Bar'
}
]
});
const bag = new TestBag(null, config, {bagData});
const r2x = new ROS2XVIZConverter(TestConverters, config, {
logger: {verbose: m => console.log(m)}
});
const result = await bag.init(r2x);
t.equals(result, true, 'Bag was correctly inited');
t.equals(bag.bagContext.start_time, 1000, 'Bag startTime was correctly inited');
t.equals(bag.bagContext.end_time, 1010, 'Bag was correctly inited');
// Ensure we iterate /tf and /tf_static
t.deepEquals(
Object.keys(bag.bagContext.frameIdToPoseMap).sort(),
['base_link', 'static_link'],
'Bag frameIdToPoseMap keys are correctly inited'
);async init() {
try {
// TODO test what happens when bagPath is not a bag
this.bag = new Bag(this.bagPath, '/current_pose');
this.metadata = await this.bag.init();
} catch (err) {
console.log(err);
}
}async init() {
try {
// TODO test what happens when bagPath is not a bag
this.bag = new Bag(this.bagPath, '/current_pose');
this.metadata = await this.bag.init();
} catch (err) {
console.log(err);
}
}export function setupCustomProvider(options) {
// Setup ROS support based on arguments
//
// Custom Converters should be added here
const ros2xvizFactory = new ROS2XVIZFactory([
GeometryPoseStamped,
NavPath,
LidarConverter,
SensorCompressedImage,
SensorImage,
VisualizationMarkerArray
]);
const {rosConfig} = options;
let config = null;
if (rosConfig) {
// topicConfig: { keyTopic, topics }
// mapping: [ { topic, name, config: {xvizStream, field} }, ... ]
const data = fs.readFileSync(rosConfig);
if (data) {
config = JSON.parse(data);tape('ROSBag#getMetadata', async t => {
const config = new ROSConfig();
const bag = new TestBag(null, config, {bagData});
const r2x = new ROS2XVIZConverter(TestConverters, config);
const result = await bag.init(r2x);
t.equals(result, true, 'Bag was correctly inited');
const builder = new XVIZMetadataBuilder();
bag.getMetadata(builder, r2x);
const metadata = builder.getMetadata();
t.ok(metadata.streams['/foo'], 'Metadata has "/foo" defined');
t.ok(metadata.streams['/bar'], 'Metadata has "/bar" defined');
t.end();
});tape('ROSBag#readMessages w/no rosConfig has all topics', async t => {
const config = new ROSConfig();
const bag = new TestBag(null, config, {bagData});
const r2x = new ROS2XVIZConverter(TestConverters, config);
const result = await bag.init(r2x);
t.equals(result, true, 'Bag was correctly inited');
const frame = await bag.readMessages();
t.equals(Object.keys(frame).length, 4, 'frame has 4 keys');
t.ok(frame['/foo'], 'readMessages returned "/foo"');
t.ok(frame['/bar'], 'readMessages returned "/bar"');
t.ok(frame['/tf'], 'readMessages returned "/tf"');
t.ok(frame['/tf_static'], 'readMessages returned "/tf_static"');
t.end();
});tape('ROSBag#readMessages w/ rosConfig has limited topics', async t => {
const config = new ROSConfig({
topicConfig: [
{
topic: '/foo',
type: 'foo_msg/Foo'
},
{
topic: '/bar',
type: 'bar_msg/Bar'
}
]
});
const bag = new TestBag(null, config, {bagData});
const r2x = new ROS2XVIZConverter(TestConverters, config);
const result = await bag.init(r2x);
t.equals(result, true, 'Bag was correctly inited');