ROS LaserScan messages

Typically: "How do I... ", "How can I... " questions
Post Reply
MattDerry
Posts: 8
Joined: 15 Feb 2013, 21:48

ROS LaserScan messages

Post by MattDerry » 12 Apr 2013, 06:15

Hello,

I'm trying to get a LaserScan message in ROS from a simulated Hokuyo laser in V-Rep. My first thought was to use the simros_strmcmd_get_range_finder_data publisher and then on the ROS side use the pointcloud_to_laserscan method to convert it, but for some reason, the LaserScan that is being generated doesn't contain any points when viewed in RViz. When I run rostopic echo on the scan topic, the points are there, but they are all set to the same max value of 11.0. It seems like something is happening that is preventing the conversion of the pointcloud (which is visualizing ok in RViz).

I'm curious if anyone has successfully done this for a laser scanner and if not, I'm hoping some people might have some ideas as to how to go about this. Thanks!

Regards,
Matt

coppelia
Site Admin
Posts: 7388
Joined: 14 Dec 2012, 00:25

Re: ROS LaserScan messages

Post by coppelia » 12 Apr 2013, 16:25

Hello Matt,

In you Hokuyo child script, you should put following code somewhere in the initialization phase:

Code: Select all

topicName=simExtROS_enablePublisher('rangeFinderData',1,simros_strmcmd_get_range_finder_data ,modelHandle,-1,'rangeDat'..objName)
and further down, make sure to always actualize the signal data in a way similar to:

Code: Select all

-- Now actualize the data:
if #points>0 then
	-- The publisher defined further up uses the data stored in signal 'rangeDat'..objName
	simSetStringSignal('rangeDat'..objName,simPackFloats(points))
end
What basically happens is:
  • you define a publisher that always publishes the data stored in a string signal
  • you need to regularly update the data in the string signal
This might look a bit like an indirect solution (i.e. via a string signal), but allows a great deal of flexibility (i.e. not only laser scanners can publish point cloud data)

Cheers

philotuxo
Posts: 6
Joined: 25 Feb 2013, 01:40

Re: ROS LaserScan messages

Post by philotuxo » 06 May 2013, 15:51

I could publish Hokuyo pointcloud data with these tricks, but one should use the object handle of a parent node of "Hokuyo_laser", for example "Hokuyo_joint", instead of the leaf node itself to avoid weird transform information as the joint continuously rotates.

Thank you.
coppelia wrote: In you Hokuyo child script, you should put following code somewhere in the initialization phase:

Code: Select all

topicName=simExtROS_enablePublisher('rangeFinderData',1,simros_strmcmd_get_range_finder_data ,modelHandle,-1,'rangeDat'..objName)
and further down, make sure to always actualize the signal data in a way similar to:

Code: Select all

-- Now actualize the data:
if #points>0 then
	-- The publisher defined further up uses the data stored in signal 'rangeDat'..objName
	simSetStringSignal('rangeDat'..objName,simPackFloats(points))
end

philotuxo
Posts: 6
Joined: 25 Feb 2013, 01:40

Re: ROS LaserScan messages

Post by philotuxo » 07 May 2013, 02:42

Hi Matt,

Did you convert pointcloud2 to laserscan?

Post Reply