Code: Select all
rostopic info topic_name
Thanks
[EDIT] On a similar note, where are the
Code: Select all
streamcmds e.g. simros_strmcmd_set_object_pose
Code: Select all
rostopic info topic_name
Code: Select all
streamcmds e.g. simros_strmcmd_set_object_pose
I understand this. Maybe I was unclear in what I was asking. I can't get the subscriber in the threaded script functioning. It works fine in a non-threaded script and updates the value of the object I want it to. However, in a threaded script, even though I can see that V-rep is subscribed to the topic, it doesn't update the value of the object. I've set up the subscriber in the initialisation stage of the threaded script. Could it be that the thread execution in the script does not allow execution of anything outside of thread function?coppelia wrote:Yes, you can use a threaded and non-threaded child script in a similar way. The way the current ROS interface works is somewhat semi-automatic: publishers will be automatically triggered in each simulation step, with appropriate data filled-in. The same happens with subscribers. This allows to enable streaming of a vision sensor image (for example) with a single line of code. And allows to enable subscription (and application) of a ROS image to a passive vision sensor also with a single line of code.
Code: Select all
simRosCallScriptFunction
Code: Select all
-- Retrive the handle of the vision sensor we wish to stream:
visionSensorHandle=simGetObjectHandle('Vision_sensor')
-- Now enable topic publishing and streaming of the vision sensor's data:
topicName=simExtROS_enablePublisher('visionSensorData',1,simros_strmcmd_get_vision_sensor_image,visionSensorHandle,0,'')
-- Retrive the handle of the passive vision sensor. We will use the passive vision sensor
-- to visualize received data:
passiveSensorHandle=simGetObjectHandle('PassiveVision_sensor')
-- Now enable a topic subscription:
simExtROS_enableSubscriber(topicName,1,simros_strmcmd_set_vision_sensor_image,passiveSensorHandle,0,'')
Code: Select all
function sysCall_threadmain()
-- Get some handles:
activeVisionSensor=sim.getObjectHandle('Vision_sensor')
passiveVisionSensor=sim.getObjectHandle('PassiveVision_sensor')
-- Enable an image publisher and subscriber:
if simROS then
print("<font color='#0F0'>ROS interface was found.</font>@html")
pub=simROS.advertise('/image', 'sensor_msgs/Image')
simROS.publisherTreatUInt8ArrayAsString(pub) -- treat uint8 arrays as strings (much faster, tables/arrays are kind of slow in Lua)
sub=simROS.subscribe('/image', 'sensor_msgs/Image', 'imageMessage_callback')
simROS.subscriberTreatUInt8ArrayAsString(sub) -- treat uint8 arrays as strings (much faster, tables/arrays are kind of slow in Lua)
else
print("<font color='#F00'>ROS interface was not found. Cannot run.</font>@html")
end
sim.setThreadResumeLocation(sim.scriptthreadresume_sensing_last,sim.scriptexecorder_normal)
sim.setThreadAutomaticSwitch(false)
while sim.getSimulationState()~=sim.simulation_advancing_abouttostop do
if simROS then
-- Publish the image of the active vision sensor:
local data,w,h=sim.getVisionSensorCharImage(activeVisionSensor)
d={}
d['header']={stamp=simROS.getTime(), frame_id="a"}
d['height']=h
d['width']=w
d['encoding']='rgb8'
d['is_bigendian']=1
d['step']=w*3
d['data']=data
simROS.publish(pub,d)
end
sim.switchThread() -- resume in next simulation step
end
end
function sysCall_cleanup()
if simROS then
-- Shut down publisher and subscriber. Not really needed from a simulation script (automatic shutdown)
simROS.shutdownPublisher(pub)
simROS.shutdownSubscriber(sub)
end
end
function sysCall_init()
end
function imageMessage_callback(msg)
-- Apply the received image to the passive vision sensor that acts as an image container
sim.setVisionSensorCharImage(passiveVisionSensor,msg.data)
end
function sysCall_cleanup()
end