Range Sensor Layer wont clear
Hi,
Hello, (Im running ROS-Kinetic, Ubuntu 16.04 - with a laserscan and an ultrasonic sensor)
I am having an issue with my costmap configuration, The range_sensor_layer firstly appears to be marking in the local costmap, and secondly, marks in the map but does not get cleared. I have limited the ultrasonic sensor to 2.0m as it just provides a range for distances.
As you can see in my configurations below, the clear_on_max_reading is set to true,
It sets a permanent marking at this range of 2.0m and this doesnt clear from the map. Also, i put obstacles in front of the ultrasonic sensor, but this doesnt get cleared once the obstacle is removed. see the picture image attached
It also throws this error.
Range sensor layer can't transform from odom to /ultrasound at 1589825801.669056
How do i fix this?
Update: Map clears now, but it still throws this error Range sensor layer can't transform from odom to /ultrasound at 1589825801.669056
How do i solve this please???
I am using an Arduino Uno at baud rate 57600 for the odom (encoders) and an Arduino Mega at baud rate at 9600 for the Ultrasonic sensors. Can this be the issue?
Ultrasonic Code
#include <SoftwareSerial.h>
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
#include <NewPing.h>
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range ( "/ultrasound3", &range_msg);
float sensoReading = 0;
#define TRIGGER_PIN_2 32
#define ECHO_PIN_2 33
#define MAX_DISTANCE 200
// NewPing setup of pins and maximum distance
NewPing sonar(TRIGGER_PIN_2, ECHO_PIN_2, MAX_DISTANCE);
char frameid[] ="/ultrasound";
void setup()
{
Serial.begin(9600);
nh.getHardware()->setBaud(9600);
nh.initNode();
nh.advertise(pub_range);
range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND;
range_msg.header.frame_id = frameid;
range_msg.field_of_view = 1.0;
range_msg.min_range = 0.0;
range_msg.max_range = 2.0;
}
long range_time;
void loop() {
float distance = sonar.ping_cm();
distance = distance/100;
Serial.print(distance);
Serial.print("m ");
if ( (millis() - range_time )>50){
range_msg.range = distance;
range_msg.header.stamp = nh.now();
pub_range.publish(&range_msg);
range_time = millis();
}
nh.spinOnce();
}
@gvdhoorn Can you please assist with this? Pleaseeeeeee
Do not call out people by name.
how did you solve the clearing issue ?
Hi, @NiamhD
I solved it by reducing the field of view to about 0.1 - 0.4