LIDAR LMS111 and rosserial delay

asked 2017-06-25 03:18:45 -0500

mtROS gravatar image

Hy there,

i have following problem: I use a LIDAR LMS111 to get an average distance to an object. The node chain looks like: LIDAR---> scan---> scan_filter---> republisher---> rosserial.

I use the scan_filter to cut out a small area from the whole scan. Then i use a own written node "republisher" to publish an average of some points to a range message. This range message gets then subscribed by a microcontroller.

Now the problem is that i have a huge delay ~ 500ms of the range information on the microcontroller. I use a baudrate of 115200. The range msg gets published with a sampling rate of 50 Hz.

Does somebody have an idea where the delay coudl come from, or a suggestion how to evaluate the timing in ROS?

Thanks in advance!

Michael

The republisher node::

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "sensor_msgs/LaserScan.h"
#include "sensor_msgs/Range.h"
#include "message_filters/subscriber.h"
#include "tf/message_filter.h"
#include "tf/transform_listener.h"
#include "filters/filter_chain.h"

// this node subscribes to the LaserScan_msg /scan_filtered topic does some average
// of the data and republishes the result to the topic of type sensor_msgs::Ranges namely
// ranges
// class in order to not use global variables
class HandelSubandPub
{
public:
sensor_msgs::Range range;
// handle subscriber and publisher
HandelSubandPub()
  {
    //Topic you want to publish
    publish_class_member = n.advertise<sensor_msgs::Range>("ranges", 1000);
    //Topic you want to subscribe
    subscribe_class_member = n.subscribe("scan_filtered", 1000,&HandelSubandPub::chatterCallback,this);
  }
void chatterCallback(const sensor_msgs::LaserScan::ConstPtr& msg_in)
    {
      //ROS_INFO("callback");
      range.header = msg_in->header;
range.range =   (msg_in->ranges[1]+msg_in->ranges[3]+msg_in->ranges[6])/3;
    publish_class_member.publish(range);
    }
private: 
    ros::NodeHandle n;
    ros::Publisher publish_class_member;
    ros::Subscriber subscribe_class_member;
};
int main(int argc, char **argv)
{
 ros::init(argc, argv, "republisher");
 HandelSubandPub HSPObject;
 ros::spin();
 return 0;
}
edit retag flag offensive close merge delete

Comments

1

Try comparing ros::Time::now() to msg_in->header.stamp in the chatterCallback. Also try with and without the scan_filter, see if that adds much delay.

lucasw gravatar image lucasw  ( 2017-06-25 06:16:48 -0500 )edit

thanks for the suggestion! How would you do the comparison?

mtROS gravatar image mtROS  ( 2017-06-25 06:36:44 -0500 )edit
1

Try adding this to chatterCallback:

ROS_INFO_STREAM(ros::Time::now() - msg_in->header.stamp);
lucasw gravatar image lucasw  ( 2017-06-25 07:30:57 -0500 )edit

Works fine, thanks but delay is just below 50ms...

mtROS gravatar image mtROS  ( 2017-06-25 07:33:59 -0500 )edit
1

So on to the next 'hop' (scan_filter -> arduino) to repeat the same measurement .. That will be slightly more difficult, as for really meaningful results you'd need to have some sort of shared clock. How did you determine the '~500 ms delay` earlier?

gvdhoorn gravatar image gvdhoorn  ( 2017-06-25 07:35:49 -0500 )edit

Sorry for that question but just to be clear. The header.stamp is the time-stamp of the corresponding laser scan message. So from the time when it has been recorded?

mtROS gravatar image mtROS  ( 2017-06-25 07:41:39 -0500 )edit
1

The header.stamp is the time-stamp of the corresponding laser scan message. So from the time when it has been recorded?

Yes.

If you copy the value of the stamp field of the Header of the scan msg to the Header of the Range msg you could determine latency along the entire processing chain.

gvdhoorn gravatar image gvdhoorn  ( 2017-06-25 07:46:18 -0500 )edit

@gvdhoorn i am moving the LIDAR- sensor with a linear axis. I know how long it takes from the go command till the motor-position is reached. I recorded the time from when the mechanical position was reached until the message from ROS reached the certain distance.

mtROS gravatar image mtROS  ( 2017-06-25 07:48:13 -0500 )edit