ROS2Interface Plugin API reference

This plugin provides an interface with the ROS2 API

simROS2.advertise

Description Advertise a topic and create a topic publisher.
Lua synopsis int publisherHandle=simROS2.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 (int): a handle to the ROS publisher
See also simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe simROS2.subscriberTreatUInt8ArrayAsString

simROS2.advertiseService

Description Advertise a service and create a service server.
Lua synopsis int serviceServerHandle=simROS2.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 (int): a handle to the ROS service server
See also simROS2.call simROS2.serviceClient simROS2.serviceClientTreatUInt8ArrayAsString simROS2.serviceServerTreatUInt8ArrayAsString simROS2.shutdownServiceClient simROS2.shutdownServiceServer

simROS2.call

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

simROS2.deleteParam

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

simROS2.getParamBool

Description Retrieve a boolean parameter from the ROS Parameter Server.
Lua synopsis bool exists, bool value=simROS2.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
See also simROS2.deleteParam simROS2.getParamDouble simROS2.getParamInt simROS2.getParamString simROS2.hasParam simROS2.searchParam simROS2.setParamBool simROS2.setParamDouble simROS2.setParamInt simROS2.setParamString

simROS2.getParamDouble

Description Retrieve a double parameter from the ROS Parameter Server.
Lua synopsis bool exists, double value=simROS2.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
See also simROS2.deleteParam simROS2.getParamBool simROS2.getParamInt simROS2.getParamString simROS2.hasParam simROS2.searchParam simROS2.setParamBool simROS2.setParamDouble simROS2.setParamInt simROS2.setParamString

simROS2.getParamInt

Description Retrieve an integer parameter from the ROS Parameter Server.
Lua synopsis bool exists, int value=simROS2.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
See also simROS2.deleteParam simROS2.getParamBool simROS2.getParamDouble simROS2.getParamString simROS2.hasParam simROS2.searchParam simROS2.setParamBool simROS2.setParamDouble simROS2.setParamInt simROS2.setParamString

simROS2.getParamString

Description Retrieve a string parameter from the ROS Parameter Server.
Lua synopsis bool exists, string value=simROS2.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
See also simROS2.deleteParam simROS2.getParamBool simROS2.getParamDouble simROS2.getParamInt simROS2.hasParam simROS2.searchParam simROS2.setParamBool simROS2.setParamDouble simROS2.setParamInt simROS2.setParamString

simROS2.getTime

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

simROS2.hasParam

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

simROS2.imageTransportAdvertise

Description Advertise a topic and create a topic publisher using ImageTransport.
Lua synopsis int publisherHandle=simROS2.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 (int): a handle to the ROS publisher
See also simROS2.advertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe simROS2.subscriberTreatUInt8ArrayAsString simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe

simROS2.imageTransportPublish

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

simROS2.imageTransportShutdownPublisher

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

simROS2.imageTransportShutdownSubscriber

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

simROS2.imageTransportSubscribe

Description Subscribe to a topic using ImageTransport.
Lua synopsis int subscriberHandle=simROS2.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 (int): a handle to the ROS subscriber
See also simROS2.advertise simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe simROS2.subscriberTreatUInt8ArrayAsString simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber

simROS2.publish

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

simROS2.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 simROS2.publisherTreatUInt8ArrayAsString(int publisherHandle)
Lua parameters
publisherHandle (int): the publisher handle
Lua return values -
See also simROS2.advertise simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe simROS2.subscriberTreatUInt8ArrayAsString

simROS2.searchParam

Description Search a parameter in the ROS Parameter Server, looking in the closest namespace.
Lua synopsis bool found, string name=simROS2.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
See also simROS2.deleteParam simROS2.getParamBool simROS2.getParamDouble simROS2.getParamInt simROS2.getParamString simROS2.hasParam simROS2.setParamBool simROS2.setParamDouble simROS2.setParamInt simROS2.setParamString

simROS2.sendTransform

Description Publish a TF transformation between frames.
Lua synopsis simROS2.sendTransform(table transform)
Lua parameters
transform (table of ): 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 -
See also simROS2.advertise simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe simROS2.subscriberTreatUInt8ArrayAsString simROS2.sendTransforms

simROS2.sendTransforms

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

simROS2.serviceClient

Description Create a service client.
Lua synopsis int serviceClientHandle=simROS2.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 (int): a handle to the ROS service client
See also simROS2.advertiseService simROS2.call simROS2.serviceClientTreatUInt8ArrayAsString simROS2.serviceServerTreatUInt8ArrayAsString simROS2.shutdownServiceClient simROS2.shutdownServiceServer

simROS2.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 simROS2.serviceClientTreatUInt8ArrayAsString(int serviceClientHandle)
Lua parameters
serviceClientHandle (int): the service client handle
Lua return values -
See also simROS2.advertiseService simROS2.call simROS2.serviceClient simROS2.serviceServerTreatUInt8ArrayAsString simROS2.shutdownServiceClient simROS2.shutdownServiceServer

simROS2.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 simROS2.serviceServerTreatUInt8ArrayAsString(int serviceServerHandle)
Lua parameters
serviceServerHandle (int): the service server handle
Lua return values -
See also simROS2.advertiseService simROS2.call simROS2.serviceClient simROS2.serviceClientTreatUInt8ArrayAsString simROS2.shutdownServiceClient simROS2.shutdownServiceServer

simROS2.setParamBool

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

simROS2.setParamDouble

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

simROS2.setParamInt

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

simROS2.setParamString

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

simROS2.shutdownPublisher

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

simROS2.shutdownServiceClient

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

simROS2.shutdownServiceServer

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

simROS2.shutdownSubscriber

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

simROS2.subscribe

Description Subscribe to a topic.
Lua synopsis int subscriberHandle=simROS2.subscribe(string topicName, string topicType, string topicCallback, int queueSize=1)
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
Lua return values
subscriberHandle (int): a handle to the ROS subscriber
See also simROS2.advertise simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscriberTreatUInt8ArrayAsString

simROS2.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 simROS2.subscriberTreatUInt8ArrayAsString(int subscriberHandle)
Lua parameters
subscriberHandle (int): the subscriber handle
Lua return values -
See also simROS2.advertise simROS2.imageTransportAdvertise simROS2.imageTransportPublish simROS2.imageTransportShutdownPublisher simROS2.imageTransportShutdownSubscriber simROS2.imageTransportSubscribe simROS2.publish simROS2.publisherTreatUInt8ArrayAsString simROS2.sendTransform simROS2.sendTransforms simROS2.shutdownPublisher simROS2.shutdownSubscriber simROS2.subscribe



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 simROS2.subscriberCallback(table message)
Lua parameters
message (table of ): the topic payload (i.e. the message)
Lua return values -
See also

imageTransportCallback

Description Callback for ROS ImageTransport subscriber.
Lua synopsis simROS2.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 -
See also