RosInterface API reference

The list of API functions below provides an interface to ROS. Those functions are part of the RosInterface. This interface naturally duplicates the C/C++ ROS API.

simExtRosInterface_advertise

Description Advertise a topic and create a topic publisher.
Lua synopsis int publisherHandle=simExtRosInterface_advertise(string topicName, string topicType, int queueSize = 1, bool latch = false)
Lua parameters
topicName: topic name, e.g.: '/cmd_vel'
topicType: topic type, e.g.: 'geometry_msgs::Twist'
queueSize: (optional) queue size
latch: (optional) latch topic
Lua return values
publisherHandle: a handle to the ROS publisher

simExtRosInterface_advertiseService

Description Advertise a service and create a service server.
Lua synopsis int serviceServerHandle=simExtRosInterface_advertiseService(string serviceName, string serviceType, string serviceCallback)
Lua parameters
serviceName: topic name, e.g.: '/cmd_vel'
serviceType: topic type, e.g.: 'geometry_msgs::Twist'
serviceCallback: 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: a handle to the ROS service server

simExtRosInterface_call

Description Call the service associated with this service client.
Lua synopsis table result=simExtRosInterface_call(int serviceClientHandle, table request)
Lua parameters
serviceClientHandle: the service client handle
request: the message to publish
Lua return values
result: the response message, if the call succeeded

simExtRosInterface_deleteParam

Description Delete a parameter in the ROS Parameter Server.
Lua synopsis simExtRosInterface_deleteParam(string name)
Lua parameters
name: name of the parameter
Lua return values -

simExtRosInterface_getParamBool

Description Retrieve a boolean parameter from the ROS Parameter Server.
Lua synopsis bool exists, bool value=simExtRosInterface_getParamBool(string name, bool defaultValue = false)
Lua parameters
name: name of the parameter
defaultValue: default value returned when parameter does not exist
Lua return values
exists: true if the param exists otherwise false
value: the value of the requested parameter

simExtRosInterface_getParamDouble

Description Retrieve a double parameter from the ROS Parameter Server.
Lua synopsis bool exists, double value=simExtRosInterface_getParamDouble(string name, double defaultValue = 0.0)
Lua parameters
name: name of the parameter
defaultValue: default value returned when parameter does not exist
Lua return values
exists: true if the param exists otherwise false
value: the value of the requested parameter

simExtRosInterface_getParamInt

Description Retrieve an integer parameter from the ROS Parameter Server.
Lua synopsis bool exists, int value=simExtRosInterface_getParamInt(string name, int defaultValue = 0)
Lua parameters
name: name of the parameter
defaultValue: default value returned when parameter does not exist
Lua return values
exists: true if the param exists otherwise false
value: the value of the requested parameter

simExtRosInterface_getParamString

Description Retrieve a string parameter from the ROS Parameter Server.
Lua synopsis bool exists, string value=simExtRosInterface_getParamString(string name, string defaultValue = )
Lua parameters
name: name of the parameter
defaultValue: default value returned when parameter does not exist
Lua return values
exists: true if the param exists otherwise false
value: the value of the requested parameter

simExtRosInterface_getTime

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

simExtRosInterface_hasParam

Description Check wether a parameter exists in the ROS Parameter Server.
Lua synopsis bool exists=simExtRosInterface_hasParam(string name)
Lua parameters
name: name of the parameter
Lua return values
exists: true if the parameter exists, false otherwise

simExtRosInterface_imageTransportAdvertise

Description Advertise a topic and create a topic publisher using ImageTransport.
Lua synopsis int publisherHandle=simExtRosInterface_imageTransportAdvertise(string topicName, int queueSize = 1)
Lua parameters
topicName: topic name, e.g.: '/cmd_vel'
queueSize: (optional) queue size
Lua return values
publisherHandle: a handle to the ROS publisher

simExtRosInterface_imageTransportPublish

Description Publish a message on the topic associated with this publisher using ImageTransport.
Lua synopsis simExtRosInterface_imageTransportPublish(int publisherHandle, string data, int width, int height, string frame_id)
Lua parameters
publisherHandle: the publisher handle
data: the image data
width: image width
height: image height
frame_id: frame id
Lua return values -

simExtRosInterface_imageTransportShutdownPublisher

Description Shutdown the advertisement associated with this publisher using ImageTransport.
Lua synopsis simExtRosInterface_imageTransportShutdownPublisher(int publisherHandle)
Lua parameters
publisherHandle: the publisher handle
Lua return values -

simExtRosInterface_imageTransportShutdownSubscriber

Description Unsubscribe the callback associated with this subscriber using ImageTransport.
Lua synopsis simExtRosInterface_imageTransportShutdownSubscriber(int subscriberHandle)
Lua parameters
subscriberHandle: the subscriber handle
Lua return values -

simExtRosInterface_imageTransportSubscribe

Description Subscribe to a topic using ImageTransport.
Lua synopsis int subscriberHandle=simExtRosInterface_imageTransportSubscribe(string topicName, string topicCallback, int queueSize = 1)
Lua parameters
topicName: topic name, e.g.: '/cmd_vel'
topicCallback: name of the callback function, which will be called as: topicCallback(string data, number width, number height)
queueSize: (optional) queue size
Lua return values
subscriberHandle: a handle to the ROS subscriber

simExtRosInterface_publish

Description Publish a message on the topic associated with this publisher.
Lua synopsis simExtRosInterface_publish(int publisherHandle, table message)
Lua parameters
publisherHandle: the publisher handle
message: the message to publish
Lua return values -

simExtRosInterface_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 simExtRosInterface_publisherTreatUInt8ArrayAsString(int publisherHandle)
Lua parameters
publisherHandle: the publisher handle
Lua return values -

simExtRosInterface_searchParam

Description Search a parameter in the ROS Parameter Server, looking in the closest namespace.
Lua synopsis bool found, string name=simExtRosInterface_searchParam(string name)
Lua parameters
name: name of the parameter
Lua return values
found: true if the parameter has been found
name: name of the parameter which has been found

simExtRosInterface_sendTransform

Description Publish a TF transformation between frames.
Lua synopsis simExtRosInterface_sendTransform(table transform)
Lua parameters
transform: 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 -

simExtRosInterface_sendTransforms

Description Publish several TF transformations between frames.
Lua synopsis simExtRosInterface_sendTransforms(table transforms)
Lua parameters
transforms: an array of geometry_msgs/TransformStamped messages
Lua return values -

simExtRosInterface_serviceClient

Description Create a service client.
Lua synopsis int serviceClientHandle=simExtRosInterface_serviceClient(string serviceName, string serviceType)
Lua parameters
serviceName: topic name, e.g.: '/cmd_vel'
serviceType: topic type, e.g.: 'geometry_msgs::Twist'
Lua return values
serviceClientHandle: a handle to the ROS service client

simExtRosInterface_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 simExtRosInterface_serviceClientTreatUInt8ArrayAsString(int serviceClientHandle)
Lua parameters
serviceClientHandle: the service client handle
Lua return values -

simExtRosInterface_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 simExtRosInterface_serviceServerTreatUInt8ArrayAsString(int serviceServerHandle)
Lua parameters
serviceServerHandle: the service server handle
Lua return values -

simExtRosInterface_setParamBool

Description Set a boolean parameter in the ROS Parameter Server.
Lua synopsis simExtRosInterface_setParamBool(string name, bool value)
Lua parameters
name: name of the parameter
value: value of the parameter
Lua return values -

simExtRosInterface_setParamDouble

Description Set a double parameter in the ROS Parameter Server.
Lua synopsis simExtRosInterface_setParamDouble(string name, double value)
Lua parameters
name: name of the parameter
value: value of the parameter
Lua return values -

simExtRosInterface_setParamInt

Description Set a integer parameter in the ROS Parameter Server.
Lua synopsis simExtRosInterface_setParamInt(string name, int value)
Lua parameters
name: name of the parameter
value: value of the parameter
Lua return values -

simExtRosInterface_setParamString

Description Set a string parameter in the ROS Parameter Server.
Lua synopsis simExtRosInterface_setParamString(string name, string value)
Lua parameters
name: name of the parameter
value: value of the parameter
Lua return values -

simExtRosInterface_shutdownPublisher

Description Shutdown the advertisement associated with this publisher.
Lua synopsis simExtRosInterface_shutdownPublisher(int publisherHandle)
Lua parameters
publisherHandle: the publisher handle
Lua return values -

simExtRosInterface_shutdownServiceClient

Description Shutdown the service client.
Lua synopsis simExtRosInterface_shutdownServiceClient(int serviceClientHandle)
Lua parameters
serviceClientHandle: the service client handle
Lua return values -

simExtRosInterface_shutdownServiceServer

Description Shutdown the service server.
Lua synopsis simExtRosInterface_shutdownServiceServer(int serviceServerHandle)
Lua parameters
serviceServerHandle: the service server handle
Lua return values -

simExtRosInterface_shutdownSubscriber

Description Unsubscribe the callback associated with this subscriber.
Lua synopsis simExtRosInterface_shutdownSubscriber(int subscriberHandle)
Lua parameters
subscriberHandle: the subscriber handle
Lua return values -

simExtRosInterface_subscribe

Description Subscribe to a topic.
Lua synopsis int subscriberHandle=simExtRosInterface_subscribe(string topicName, string topicType, string topicCallback, int queueSize = 1)
Lua parameters
topicName: topic name, e.g.: '/cmd_vel'
topicType: topic type, e.g.: 'geometry_msgs::Twist'
topicCallback: 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: (optional) queue size
Lua return values
subscriberHandle: a handle to the ROS subscriber

simExtRosInterface_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 simExtRosInterface_subscriberTreatUInt8ArrayAsString(int subscriberHandle)
Lua parameters
subscriberHandle: the subscriber handle
Lua return values -