ROS Plugin API reference

This plugin provides an interface with the ROS API

simROS.advertise
simROS.advertiseService
simROS.call
simROS.deleteParam
simROS.getParamBool
simROS.getParamDouble
simROS.getParamInt
simROS.getParamString
simROS.getTime
simROS.hasParam
simROS.imageTransportAdvertise
simROS.imageTransportPublish
simROS.imageTransportShutdownPublisher
simROS.imageTransportShutdownSubscriber
simROS.imageTransportSubscribe
simROS.publish
simROS.publisherTreatUInt8ArrayAsString
simROS.searchParam
simROS.sendTransform
simROS.sendTransforms
simROS.serviceClient
simROS.serviceClientTreatUInt8ArrayAsString
simROS.serviceServerTreatUInt8ArrayAsString
simROS.setParamBool
simROS.setParamDouble
simROS.setParamInt
simROS.setParamString
simROS.shutdownPublisher
simROS.shutdownServiceClient
simROS.shutdownServiceServer
simROS.shutdownSubscriber
simROS.subscribe
simROS.subscriberTreatUInt8ArrayAsString

simROS.advertise

Description Advertise a topic and create a topic publisher.
Lua synopsis string publisherHandle=simROS.advertise(string topicName, string topicType, int queueSize=1, bool latch=false)
Lua parameters
topicName (string): topic name, e.g.: '/cmd_vel'
topicType (string): topic type, e.g.: 'geometry_msgs::Twist'
queueSize (int, default: 1): (optional) queue size
latch (bool, default: false): (optional) latch topic
Lua return values
publisherHandle (string): a handle to the ROS publisher
Python synopsis string publisherHandle=simROS.advertise(string topicName, string topicType, int queueSize=1, bool latch=false)
See also simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString

simROS.advertiseService

Description Advertise a service and create a service server.
Lua synopsis string serviceServerHandle=simROS.advertiseService(string serviceName, string serviceType, string serviceCallback)
Lua parameters
serviceName (string): topic name, e.g.: '/cmd_vel'
serviceType (string): topic type, e.g.: 'geometry_msgs::Twist'
serviceCallback (string): name of the callback function, which will be called with a single argument of type table containing the service request payload; it must return another table containing the response
Lua return values
serviceServerHandle (string): a handle to the ROS service server
Python synopsis string serviceServerHandle=simROS.advertiseService(string serviceName, string serviceType, string serviceCallback)
See also simROS.call simROS.serviceClient simROS.serviceClientTreatUInt8ArrayAsString simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceClient simROS.shutdownServiceServer

simROS.call

Description Call the service associated with this service client.
Lua synopsis table result=simROS.call(string serviceClientHandle, table request)
Lua parameters
serviceClientHandle (string): the service client handle
request (table): the message to publish
Lua return values
result (table): the response message, if the call succeeded
Python synopsis list result=simROS.call(string serviceClientHandle, list request)
See also simROS.advertiseService simROS.serviceClient simROS.serviceClientTreatUInt8ArrayAsString simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceClient simROS.shutdownServiceServer

simROS.deleteParam

Description Delete a parameter in the ROS Parameter Server.
Lua synopsis simROS.deleteParam(string name)
Lua parameters
name (string): name of the parameter
Lua return values -
Python synopsis simROS.deleteParam(string name)
See also simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.getParamBool

Description Retrieve a boolean parameter from the ROS Parameter Server.
Lua synopsis bool exists, bool value=simROS.getParamBool(string name, bool defaultValue=false)
Lua parameters
name (string): name of the parameter
defaultValue (bool, default: false): default value returned when parameter does not exist
Lua return values
exists (bool): true if the param exists otherwise false
value (bool): the value of the requested parameter
Python synopsis bool exists, bool value=simROS.getParamBool(string name, bool defaultValue=false)
See also simROS.deleteParam simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.getParamDouble

Description Retrieve a double parameter from the ROS Parameter Server.
Lua synopsis bool exists, double value=simROS.getParamDouble(string name, double defaultValue=0.0)
Lua parameters
name (string): name of the parameter
defaultValue (double, default: 0.0): default value returned when parameter does not exist
Lua return values
exists (bool): true if the param exists otherwise false
value (double): the value of the requested parameter
Python synopsis bool exists, double value=simROS.getParamDouble(string name, double defaultValue=0.0)
See also simROS.deleteParam simROS.getParamBool simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.getParamInt

Description Retrieve an integer parameter from the ROS Parameter Server.
Lua synopsis bool exists, int value=simROS.getParamInt(string name, int defaultValue=0)
Lua parameters
name (string): name of the parameter
defaultValue (int, default: 0): default value returned when parameter does not exist
Lua return values
exists (bool): true if the param exists otherwise false
value (int): the value of the requested parameter
Python synopsis bool exists, int value=simROS.getParamInt(string name, int defaultValue=0)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.getParamString

Description Retrieve a string parameter from the ROS Parameter Server.
Lua synopsis bool exists, string value=simROS.getParamString(string name, string defaultValue="")
Lua parameters
name (string): name of the parameter
defaultValue (string, default: ""): default value returned when parameter does not exist
Lua return values
exists (bool): true if the param exists otherwise false
value (string): the value of the requested parameter
Python synopsis bool exists, string value=simROS.getParamString(string name, string defaultValue="")
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.getTime

Description Return the current ROS time (i.e. the time returned by ros::Time::now()).
Lua synopsis double time=simROS.getTime(int flag=0)
Lua parameters
flag (int, default: 0): unused: set to zero
Lua return values
time (double): ROS time expressed in seconds
Python synopsis double time=simROS.getTime(int flag=0)
See also

simROS.hasParam

Description Check wether a parameter exists in the ROS Parameter Server.
Lua synopsis bool exists=simROS.hasParam(string name)
Lua parameters
name (string): name of the parameter
Lua return values
exists (bool): true if the parameter exists, false otherwise
Python synopsis bool exists=simROS.hasParam(string name)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.imageTransportAdvertise

Description Advertise a topic and create a topic publisher using ImageTransport.
Lua synopsis string publisherHandle=simROS.imageTransportAdvertise(string topicName, int queueSize=1)
Lua parameters
topicName (string): topic name, e.g.: '/cmd_vel'
queueSize (int, default: 1): (optional) queue size
Lua return values
publisherHandle (string): a handle to the ROS publisher
Python synopsis string publisherHandle=simROS.imageTransportAdvertise(string topicName, int queueSize=1)
See also simROS.advertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe

simROS.imageTransportPublish

Description Publish a message on the topic associated with this publisher using ImageTransport.
Lua synopsis simROS.imageTransportPublish(string publisherHandle, string data, int width, int height, string frame_id)
Lua parameters
publisherHandle (string): the publisher handle
data (string): the image data
width (int): image width
height (int): image height
frame_id (string): frame id
Lua return values -
Python synopsis simROS.imageTransportPublish(string publisherHandle, string data, int width, int height, string frame_id)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.imageTransportAdvertise simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe

simROS.imageTransportShutdownPublisher

Description Shutdown the advertisement associated with this publisher using ImageTransport.
Lua synopsis simROS.imageTransportShutdownPublisher(string publisherHandle)
Lua parameters
publisherHandle (string): the publisher handle
Lua return values -
Python synopsis simROS.imageTransportShutdownPublisher(string publisherHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe

simROS.imageTransportShutdownSubscriber

Description Unsubscribe the callback associated with this subscriber using ImageTransport.
Lua synopsis simROS.imageTransportShutdownSubscriber(string subscriberHandle)
Lua parameters
subscriberHandle (string): the subscriber handle
Lua return values -
Python synopsis simROS.imageTransportShutdownSubscriber(string subscriberHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportSubscribe

simROS.imageTransportSubscribe

Description Subscribe to a topic using ImageTransport.
Lua synopsis string subscriberHandle=simROS.imageTransportSubscribe(string topicName, string topicCallback, int queueSize=1)
Lua parameters
topicName (string): topic name, e.g.: '/cmd_vel'
topicCallback (string): name of the callback function, which will be called as: topicCallback(string data, number width, number height)
queueSize (int, default: 1): (optional) queue size
Lua return values
subscriberHandle (string): a handle to the ROS subscriber
Python synopsis string subscriberHandle=simROS.imageTransportSubscribe(string topicName, string topicCallback, int queueSize=1)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber

simROS.publish

Description Publish a message on the topic associated with this publisher.
Lua synopsis simROS.publish(string publisherHandle, table message)
Lua parameters
publisherHandle (string): the publisher handle
message (table): the message to publish
Lua return values -
Python synopsis simROS.publish(string publisherHandle, list message)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString

simROS.publisherTreatUInt8ArrayAsString

Description After calling this function, this publisher will treat uint8 arrays as string. Using strings should be in general much faster that using int arrays in Lua.
Lua synopsis simROS.publisherTreatUInt8ArrayAsString(string publisherHandle)
Lua parameters
publisherHandle (string): the publisher handle
Lua return values -
Python synopsis simROS.publisherTreatUInt8ArrayAsString(string publisherHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString

simROS.searchParam

Description Search a parameter in the ROS Parameter Server, looking in the closest namespace.
Lua synopsis bool found, string name=simROS.searchParam(string name)
Lua parameters
name (string): name of the parameter
Lua return values
found (bool): true if the parameter has been found
name (string): name of the parameter which has been found
Python synopsis bool found, string name=simROS.searchParam(string name)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.sendTransform

Description Publish a TF transformation between frames.
Lua synopsis simROS.sendTransform(table transform)
Lua parameters
transform (table): the transformation expressed as a geometry_msgs/TransformStamped message, i.e. {header={stamp=timeStamp, frame_id='...'}, child_frame_id='...', transform={translation={x=..., y=..., z=...}, rotation={x=..., y=..., z=..., w=...}}}
Lua return values -
Python synopsis simROS.sendTransform(list transform)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.sendTransforms

simROS.sendTransforms

Description Publish several TF transformations between frames.
Lua synopsis simROS.sendTransforms(table transforms)
Lua parameters
transforms (table): an array of geometry_msgs/TransformStamped messages
Lua return values -
Python synopsis simROS.sendTransforms(list transforms)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString simROS.sendTransform

simROS.serviceClient

Description Create a service client.
Lua synopsis string serviceClientHandle=simROS.serviceClient(string serviceName, string serviceType)
Lua parameters
serviceName (string): topic name, e.g.: '/cmd_vel'
serviceType (string): topic type, e.g.: 'geometry_msgs::Twist'
Lua return values
serviceClientHandle (string): a handle to the ROS service client
Python synopsis string serviceClientHandle=simROS.serviceClient(string serviceName, string serviceType)
See also simROS.advertiseService simROS.call simROS.serviceClientTreatUInt8ArrayAsString simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceClient simROS.shutdownServiceServer

simROS.serviceClientTreatUInt8ArrayAsString

Description After calling this function, this service client will treat uint8 arrays as string. Using strings should be in general much faster that using int arrays in Lua.
Lua synopsis simROS.serviceClientTreatUInt8ArrayAsString(string serviceClientHandle)
Lua parameters
serviceClientHandle (string): the service client handle
Lua return values -
Python synopsis simROS.serviceClientTreatUInt8ArrayAsString(string serviceClientHandle)
See also simROS.advertiseService simROS.call simROS.serviceClient simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceClient simROS.shutdownServiceServer

simROS.serviceServerTreatUInt8ArrayAsString

Description After calling this function, this service server will treat uint8 arrays as string. Using strings should be in general much faster that using int arrays in Lua.
Lua synopsis simROS.serviceServerTreatUInt8ArrayAsString(string serviceServerHandle)
Lua parameters
serviceServerHandle (string): the service server handle
Lua return values -
Python synopsis simROS.serviceServerTreatUInt8ArrayAsString(string serviceServerHandle)
See also simROS.advertiseService simROS.call simROS.serviceClient simROS.serviceClientTreatUInt8ArrayAsString simROS.shutdownServiceClient simROS.shutdownServiceServer

simROS.setParamBool

Description Set a boolean parameter in the ROS Parameter Server.
Lua synopsis simROS.setParamBool(string name, bool value)
Lua parameters
name (string): name of the parameter
value (bool): value of the parameter
Lua return values -
Python synopsis simROS.setParamBool(string name, bool value)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamDouble simROS.setParamInt simROS.setParamString

simROS.setParamDouble

Description Set a double parameter in the ROS Parameter Server.
Lua synopsis simROS.setParamDouble(string name, double value)
Lua parameters
name (string): name of the parameter
value (double): value of the parameter
Lua return values -
Python synopsis simROS.setParamDouble(string name, double value)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamInt simROS.setParamString

simROS.setParamInt

Description Set a integer parameter in the ROS Parameter Server.
Lua synopsis simROS.setParamInt(string name, int value)
Lua parameters
name (string): name of the parameter
value (int): value of the parameter
Lua return values -
Python synopsis simROS.setParamInt(string name, int value)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamString

simROS.setParamString

Description Set a string parameter in the ROS Parameter Server.
Lua synopsis simROS.setParamString(string name, string value)
Lua parameters
name (string): name of the parameter
value (string): value of the parameter
Lua return values -
Python synopsis simROS.setParamString(string name, string value)
See also simROS.deleteParam simROS.getParamBool simROS.getParamDouble simROS.getParamInt simROS.getParamString simROS.hasParam simROS.searchParam simROS.setParamBool simROS.setParamDouble simROS.setParamInt

simROS.shutdownPublisher

Description Shutdown the advertisement associated with this publisher.
Lua synopsis simROS.shutdownPublisher(string publisherHandle)
Lua parameters
publisherHandle (string): the publisher handle
Lua return values -
Python synopsis simROS.shutdownPublisher(string publisherHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownSubscriber simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString

simROS.shutdownServiceClient

Description Shutdown the service client.
Lua synopsis simROS.shutdownServiceClient(string serviceClientHandle)
Lua parameters
serviceClientHandle (string): the service client handle
Lua return values -
Python synopsis simROS.shutdownServiceClient(string serviceClientHandle)
See also simROS.advertiseService simROS.call simROS.serviceClient simROS.serviceClientTreatUInt8ArrayAsString simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceServer

simROS.shutdownServiceServer

Description Shutdown the service server.
Lua synopsis simROS.shutdownServiceServer(string serviceServerHandle)
Lua parameters
serviceServerHandle (string): the service server handle
Lua return values -
Python synopsis simROS.shutdownServiceServer(string serviceServerHandle)
See also simROS.advertiseService simROS.call simROS.serviceClient simROS.serviceClientTreatUInt8ArrayAsString simROS.serviceServerTreatUInt8ArrayAsString simROS.shutdownServiceClient

simROS.shutdownSubscriber

Description Unsubscribe the callback associated with this subscriber.
Lua synopsis simROS.shutdownSubscriber(string subscriberHandle)
Lua parameters
subscriberHandle (string): the subscriber handle
Lua return values -
Python synopsis simROS.shutdownSubscriber(string subscriberHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.subscribe simROS.subscriberTreatUInt8ArrayAsString

simROS.subscribe

Description Subscribe to a topic.
Lua synopsis string subscriberHandle=simROS.subscribe(string topicName, string topicType, string topicCallback, int queueSize=1, transport_hints transportHints={})
Lua parameters
topicName (string): topic name, e.g.: '/cmd_vel'
topicType (string): topic type, e.g.: 'geometry_msgs::Twist'
topicCallback (string): name of the callback function, which will be called with a single argument of type table containing the message payload, e.g.: {linear={x=1.5, y=0.0, z=0.0}, angular={x=0.0, y=0.0, z=-2.3}}
queueSize (int, default: 1): (optional) queue size
transportHints (transport_hints, default: {}): (optional) transport hints
Lua return values
subscriberHandle (string): a handle to the ROS subscriber
Python synopsis string subscriberHandle=simROS.subscribe(string topicName, string topicType, string topicCallback, int queueSize=1, transport_hints transportHints={})
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscriberTreatUInt8ArrayAsString

simROS.subscriberTreatUInt8ArrayAsString

Description After calling this function, this subscriber will treat uint8 arrays as string. Using strings should be in general much faster that using int arrays in Lua.
Lua synopsis simROS.subscriberTreatUInt8ArrayAsString(string subscriberHandle)
Lua parameters
subscriberHandle (string): the subscriber handle
Lua return values -
Python synopsis simROS.subscriberTreatUInt8ArrayAsString(string subscriberHandle)
See also simROS.advertise simROS.imageTransportAdvertise simROS.imageTransportPublish simROS.imageTransportShutdownPublisher simROS.imageTransportShutdownSubscriber simROS.imageTransportSubscribe simROS.publish simROS.publisherTreatUInt8ArrayAsString simROS.sendTransform simROS.sendTransforms simROS.shutdownPublisher simROS.shutdownSubscriber simROS.subscribe



Data structures

Data structures are used to pass complex data around. Create data structures in Lua in the form of a map, e.g.: {line_size=3, add_to_legend=false, selectable=true}

transport_hints

Description
Fields
transports (table of string, default: {}): the list of transports to use. allowed values are 'reliable', 'unreliable', 'tcp', 'udp' (the last two being synonyms of the first two respectively). transports appearing earlier in the list have higher priority. e.g.: {'unreliable','reliable'} specifies that you would prefer an unreliable transport, followed by a reliable one.
tcpNoDelay (bool, default: false):
maxDatagramSize (int, default: 0):
See also



Script functions

Script functions are used to call some lua code from the plugin side (tipically used for event handlers).

subscriberCallback

Description Callback for ROS subscriber.
Lua synopsis simROS.subscriberCallback(table message)
Lua parameters
message (table): the topic payload (i.e. the message)
Lua return values -
Python synopsis simROS.subscriberCallback(list message)
See also

imageTransportCallback

Description Callback for ROS ImageTransport subscriber.
Lua synopsis simROS.imageTransportCallback(string data, int width, int height)
Lua parameters
data (string): the image data
width (int): image width
height (int): image height
Lua return values -
Python synopsis simROS.imageTransportCallback(string data, int width, int height)
See also