-
Notifications
You must be signed in to change notification settings - Fork 87
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
How to view laser scan on navigation grid? #106
Comments
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
I got it working now. it is a TF between
|
Hi, the getYawFromQuat is:
and you can get base_footprint_tf from this:
|
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:
|
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?
|
i have same |
You must check the /front/scan or /scan, in the code we have: |
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. |
Can anyone explain...Me please how to work with this ROS WEB BRIDGE Thanks in advance.. Am I need to launch any simulation package.. |
Help me which distro It was working... |
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
The text was updated successfully, but these errors were encountered: