ros2djs
ros2djs copied to clipboard
How to view laser scan on navigation grid?
How to view laser scan data on top of map grid on ROS web interface? I can view using ROS3djs but i want to view it on ROS2djs. is it possible?
Thanks in advance
Seems like a laser scan is not implemented in ROS2D (yet). Feel free to add it.
Seems like a laser scan is not implemented in ROS2D (yet). Feel free to add it.
Do you have a reference site or an example file?
Thanks in advance
I think the classes in the models folder are the closest starting point.
In Ros2djs it is not impleneted, but you can implement that like this function, I implemented and it is working properly:
function displayLaserScan() {
let marker_radius = 0.03;
let marker_fill_color = createjs.Graphics.getRGB(255, 0, 0, 1.0);
let laser_listener = new ROSLIB.Topic({
ros: local_ros,
name: ROS_CONFIG.LASER_TOPIC,
messageType: 'sensor_msgs/LaserScan'});
let prev_markers = null;
laser_listener.subscribe(function(msg){
const num = msg.ranges.length
const angles = Array.from({length: num}, (_, i) => msg.angle_min + (msg.angle_max - msg.angle_min) / num * i);
const poses_2d = angles.flatMap((angle, index) => {
const range = msg.ranges[index];
if (range > msg.range_min && range < msg.range_max) {
return [[Math.cos(angle) * range, Math.sin(angle) * range, -angle]]
}
return [] // Skip this point
});
if (base_footprint_tf === null) {
console.log('no tf');
return;
}
// TODO: We might be able to apply the tf transform to the container itself, and dont have to do it on each pose.
// Init the graphics component
const scan_markers = new createjs.Container();
const graphics = new createjs.Graphics().beginFill(marker_fill_color).drawCircle(0, 0, marker_radius).endFill();
// Transform each point and add it to the graphics
poses_2d.forEach(pt => {
// pt[2] += Math.PI / 2
const pose = new ROSLIB.Pose({
position: new ROSLIB.Vector3({
x: pt[0], y: pt[1], z: 0
}), orientation: new ROSLIB.Quaternion({
x: 0, y: 0, z: Math.cos(pt[2]), w: Math.sin(pt[2])
})
});
pose.applyTransform(base_footprint_tf)
const marker = new createjs.Shape(graphics)
marker.x = pose.position.x;
marker.y = -pose.position.y;
marker.rotation = - getYawFromQuat(pose.orientation).toFixed(2);
scan_markers.addChild(marker)
});
// TODO: Just update the old one, dont make new ones everytime
if (this.prev_markers !== null){
viewer.scene.removeChild(prev_markers);
}
viewer.addObject(scan_markers);
prev_markers = scan_markers;
});
}
how do I get base_footprint_tf and this function getYawFromQuat?
I got the laser scan display on the map but it seems that all points miss place.
I get base_footprint_tf
from
var tfClient = new ROSLIB.TFClient({
ros: this.rbServer,
angularThres: 0.01,
transThres: 0.01,
rate: 10.0,
fixedFrame: "map",
serverName: "tf2_web_republisher",
});
//console.log(tfClient);
tfClient.subscribe(
"base_footprint",
function (tf) {
//console.log(tf);
this.base_footprint_tf = tf;
}.bind(this)
);
I got it working now. it is a TF between map
frame and laser
frame.
var tfClient = new ROSLIB.TFClient({
ros: this.rbServer,
angularThres: 0.01,
transThres: 0.01,
rate: 10.0,
fixedFrame: "map",
serverName: "tf2_web_republisher",
});
//console.log(tfClient);
tfClient.subscribe(
"laser",
function (tf) {
//console.log(tf);
this.base_footprint_tf = tf;
}.bind(this)
);
Hi, the getYawFromQuat is:
function getYawFromQuat(q) {
var quat = new Three.Quaternion(q.x, q.y, q.z, q.w);
var yaw = new Three.Euler().setFromQuaternion(quat);
return yaw["_z"] * (180 / Math.PI);
}
and you can get base_footprint_tf from this:
var base_footprint_tf = null;
var tf_client = new ROSLIB.TFClient({
ros: ros,
fixedFrame: "map",
angularThres: 0.01,
transThres: 0.01
});
tf_client.subscribe("/laser", function(tf) { //Maybe /scan in your project
base_footprint_tf = tf;
});
The result may be like this image:
My result is ok
However, I have to reduce the number of points 5 times. Otherwise, it will be very slow. My lidar gives about 1000 points. I observe that it can render about 200 points without slowing the system down.
you can change poses_2d's flatmap in the code and replace poses_2d.forEach with for statement.
I change the display laserscan() function to show half of points:
function displayLaserScan(ros) {
// console.log('start laser scan');
let topic = ROS_CONFIG.LASER_TOPIC ;//"/sick_safetyscanners/scan";
let marker_radius = 0.03;
let marker_fill_color = createjs.Graphics.getRGB(255, 0, 0, 1.0);
let laser_listener = new ROSLIB.Topic({
ros: ros,
name: topic,
messageType: 'sensor_msgs/LaserScan'});
let prev_markers = null;
laser_listener.subscribe(function(msg){
const num = msg.ranges.length
const angles = Array.from({length: num}, (_, i) => msg.angle_min + (msg.angle_max - msg.angle_min) / num * i);
const poses_2d = angles.flatMap((angle, index) => {
const range = msg.ranges[index];
if (range > msg.range_min && range < msg.range_max) {
return [[Math.cos(angle) * range, Math.sin(angle) * range, -angle]]
}
return [] // Skip this point
});
if (base_footprint_tf === null) {
console.log('no tf');
return;
}
// TODO: We might be able to apply the tf transform to the container itself, and dont have to do it on each pose.
// Init the graphics component
const scan_markers = new createjs.Container();
const graphics = new createjs.Graphics().beginFill(marker_fill_color).drawCircle(0, 0, marker_radius).endFill();
// Transform each point and add it to the graphics
//console.log('pose 2d',poses_2d.length);
for(let i=0;i<poses_2d.length;i++){
if(i%2 === 0){
let pt = poses_2d[i];
const pose = new ROSLIB.Pose({
position: new ROSLIB.Vector3({
x: pt[0], y: pt[1], z: 0
}), orientation: new ROSLIB.Quaternion({
x: 0, y: 0, z: Math.cos(pt[2]), w: Math.sin(pt[2])
})
});
pose.applyTransform(base_footprint_tf);
const marker = new createjs.Shape(graphics);
marker.x = pose.position.x;
marker.y = -pose.position.y;
marker.rotation = viewer.scene.rosQuaternionToGlobalTheta(pose.orientation);
scan_markers.addChild(marker);
}
}
// TODO: Just update the old one, dont make new ones everytime
if (this.prev_markers !== null){
viewer.scene.removeChild(prev_markers);
}
prev_markers = scan_markers;
viewer.addObject(prev_markers);
});
}
I change the display laserscan() function to show half of points:
function displayLaserScan(ros) { // console.log('start laser scan'); let topic = ROS_CONFIG.LASER_TOPIC ;//"/sick_safetyscanners/scan"; let marker_radius = 0.03; let marker_fill_color = createjs.Graphics.getRGB(255, 0, 0, 1.0); let laser_listener = new ROSLIB.Topic({ ros: ros, name: topic, messageType: 'sensor_msgs/LaserScan'}); let prev_markers = null; laser_listener.subscribe(function(msg){ const num = msg.ranges.length const angles = Array.from({length: num}, (_, i) => msg.angle_min + (msg.angle_max - msg.angle_min) / num * i); const poses_2d = angles.flatMap((angle, index) => { const range = msg.ranges[index]; if (range > msg.range_min && range < msg.range_max) { return [[Math.cos(angle) * range, Math.sin(angle) * range, -angle]] } return [] // Skip this point }); if (base_footprint_tf === null) { console.log('no tf'); return; } // TODO: We might be able to apply the tf transform to the container itself, and dont have to do it on each pose. // Init the graphics component const scan_markers = new createjs.Container(); const graphics = new createjs.Graphics().beginFill(marker_fill_color).drawCircle(0, 0, marker_radius).endFill(); // Transform each point and add it to the graphics //console.log('pose 2d',poses_2d.length); for(let i=0;i<poses_2d.length;i++){ if(i%2 === 0){ let pt = poses_2d[i]; const pose = new ROSLIB.Pose({ position: new ROSLIB.Vector3({ x: pt[0], y: pt[1], z: 0 }), orientation: new ROSLIB.Quaternion({ x: 0, y: 0, z: Math.cos(pt[2]), w: Math.sin(pt[2]) }) }); pose.applyTransform(base_footprint_tf); const marker = new createjs.Shape(graphics); marker.x = pose.position.x; marker.y = -pose.position.y; marker.rotation = viewer.scene.rosQuaternionToGlobalTheta(pose.orientation); scan_markers.addChild(marker); } } // TODO: Just update the old one, dont make new ones everytime if (this.prev_markers !== null){ viewer.scene.removeChild(prev_markers); } prev_markers = scan_markers; viewer.addObject(prev_markers); }); }
Hi, i know this is a while ago. But i am having trouble recreating your solution. Could you tell me if my html file should work?
<html>
<head>
<meta charset="utf-8" />
<script type="text/javascript" src="easeljs.min.js"></script>
<script type="text/javascript" src="eventemitter2.js"></script>
<script type="text/javascript" src="roslib.min.js"></script>
<script type="text/javascript" src="ros2d.js"></script>
<script type="text/javascript" type="text/javascript">
/**
* Setup all visualization elements when the page is loaded.
*/
function init() {
// Connect to ROS.
var ros = new ROSLIB.Ros({
url : 'ws://0.0.0.0:9090'
});
// Create the main viewer.
var viewer = new ROS2D.Viewer({
divID : 'viewer',
width : 600,
height : 500
});
function getYawFromQuat(q) {
var quat = new Three.Quaternion(q.x, q.y, q.z, q.w);
var yaw = new Three.Euler().setFromQuaternion(quat);
return yaw["_z"] * (180 / Math.PI);
}
var base_footprint_tf = null;
var tf_client = new ROSLIB.TFClient({
ros: ros,
fixedFrame: "map",
angularThres: 0.01,
transThres: 0.01
});
tf_client.subscribe("/front/scan", function(tf) { //Maybe /scan in your project
base_footprint_tf = tf;
});
function displayLaserScan(ros) {
// console.log('start laser scan');
let topic = "/front/scan" ;//"/sick_safetyscanners/scan";
let marker_radius = 0.03;
let marker_fill_color = createjs.Graphics.getRGB(255, 0, 0, 1.0);
let laser_listener = new ROSLIB.Topic({
ros: ros,
name: topic,
messageType: 'sensor_msgs/LaserScan'});
let prev_markers = null;
laser_listener.subscribe(function(msg){
const num = msg.ranges.length
const angles = Array.from({length: num}, (_, i) => msg.angle_min + (msg.angle_max - msg.angle_min) / num * i);
const poses_2d = angles.flatMap((angle, index) => {
const range = msg.ranges[index];
if (range > msg.range_min && range < msg.range_max) {
return [[Math.cos(angle) * range, Math.sin(angle) * range, -angle]]
}
return [] // Skip this point
});
if (base_footprint_tf === null) {
console.log('no tf');
return;
}
// TODO: We might be able to apply the tf transform to the container itself, and dont have to do it on each pose.
// Init the graphics component
const scan_markers = new createjs.Container();
const graphics = new createjs.Graphics().beginFill(marker_fill_color).drawCircle(0, 0, marker_radius).endFill();
// Transform each point and add it to the graphics
//console.log('pose 2d',poses_2d.length);
for(let i=0;i<poses_2d.length;i++){
if(i%2 === 0){
let pt = poses_2d[i];
const pose = new ROSLIB.Pose({
position: new ROSLIB.Vector3({
x: pt[0], y: pt[1], z: 0
}), orientation: new ROSLIB.Quaternion({
x: 0, y: 0, z: Math.cos(pt[2]), w: Math.sin(pt[2])
})
});
pose.applyTransform(base_footprint_tf);
const marker = new createjs.Shape(graphics);
marker.x = pose.position.x;
marker.y = -pose.position.y;
marker.rotation = viewer.scene.rosQuaternionToGlobalTheta(pose.orientation);
scan_markers.addChild(marker);
}
}
// TODO: Just update the old one, dont make new ones everytime
if (this.prev_markers !== null){
viewer.scene.removeChild(prev_markers);
}
prev_markers = scan_markers;
viewer.addObject(prev_markers);
});
}
}
</script>
</head>
<body onload="init()">
<h1>Simple Map Example</h1>
<div id="viewer"></div>
</body>
</html>```
i have same question。 i will show ('no tf');
You must check the /front/scan or /scan, in the code we have: tf_client.subscribe("/front/scan", function(tf) { //Maybe /scan in your project base_footprint_tf = tf; }); if do not receive anything from client. it returns no tf.
Can you please share the complete code as I am having issues in viewing laser scan on map? I have tried as per the above instructions but unable to view laserscan. Although I am able to view in Ros3Djs. Thanks in advance
Can anyone explain...Me please how to work with this ROS WEB BRIDGE
Thanks in advance..
Am I need to launch any simulation package.. Then create any html file .. And how to visualize my robot in web .. Can anyone explain me please
Help me which distro It was working...