
ROS publisher types
streamCmd: simros_strmcmd_get_and_clear_string_signal
Description
|
Enables streaming of a string signal. The signal is cleared after each post. See here for information on how to enable data streaming. See also the service equivalent (simRosGetAndClearStringSignal) for details. See also simros_strmcmd_get_string_signal. |
Enabling parameters |
auxInt1: (not used)
auxInt2: (not used)
auxString: signal name
|
Streamed data
|
std_msgs::String: the desired signal value
|
streamCmd: simros_strmcmd_get_array_parameter
Description
|
Enables streaming of an array parameter. See here for information on how to enable data streaming. See also the service equivalent (simRosGetArrayParameter) for details. See also simros_strmcmd_set_array_parameter. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
geometry_msgs::Point32: the desired array values
|
streamCmd: simros_strmcmd_get_boolean_parameter
Description
|
Enables streaming of a Boolean parameter. See here for information on how to enable data streaming. See also the service equivalent (simRosGetBooleanParameter) for details. See also simros_strmcmd_set_boolean_parameter. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::UInt8: the desired Boolean value
|
streamCmd: simros_strmcmd_get_dialog_result
Description
|
Enables streaming of a dialog's result value. See here for information on how to enable data streaming. See also the service equivalent (simRosGetDialogResult) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
|
streamCmd: simros_strmcmd_get_floating_parameter
Description
|
Enables streaming of a floating parameter. See here for information on how to enable data streaming. See also the service equivalent (simRosGetFloatingParameter) for details. See also simros_strmcmd_set_floating_parameter. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Float32: the desired float value
|
streamCmd: simros_strmcmd_get_float_signal
Description
|
Enables streaming of a float signal. See here for information on how to enable data streaming. See also the service equivalent (simRosGetFloatSignal) for details. See also simros_strmcmd_set_float_signal. |
Enabling parameters |
auxInt1: (not used)
auxInt2: (not used)
auxString: the signal name
|
Streamed data
|
std_msgs::Float32: the desired signal value
|
topic name: info
Description
|
The topic info is an exception: it will start streaming data as long as V-REP is running (i.e. a publisher for that topic does not need to be activated). Simulator state information will be streamed under that topic. See also the service equivalent (simRosGetInfo) for details. |
Streamed data
|
vrep_common::VrepInfo::headerInfo (Header): header information
vrep_common::VrepInfo::simulatorState (Int32): the simulator state, bit-coded:
bit0 set: simulation not stopped
bit1 set: simulation paused
bit2 set: real-time switch on
bit3-bit5: the edit mode type (0=no edit mode, 1=triangle, 2=vertex, 3=edge, 4=path, 5=UI)
vrep_common::VrepInfo::simulatonTime (Float32): the simulation time
vrep_common::VrepInfo::timeStep (Float32): the simulation time step
|
streamCmd: simros_strmcmd_get_integer_parameter
Description
|
Enables streaming of an integer parameter. See here for information on how to enable data streaming. See also the service equivalent (simRosGetIntegerParameter) for details. See also simros_strmcmd_set_integer_parameter. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32: the desired value
|
streamCmd: simros_strmcmd_get_integer_signal
Description
|
Enables streaming of an integer signal. See here for information on how to enable data streaming. See also the service equivalent (simRosGetIntegerSignal) for details. See also simros_strmcmd_set_integer_signal. |
Enabling parameters |
auxInt1: (not used)
auxInt2: (not used)
auxString: signal name
|
Streamed data
|
std_msgs::Int32: the desired signal value
|
streamCmd: simros_strmcmd_get_joint_state
streamCmd: simros_strmcmd_get_object_float_parameter
streamCmd: simros_strmcmd_get_object_int_parameter
streamCmd: simros_strmcmd_get_object_parent
Description
|
Enables streaming of an object's parent handle. See here for information on how to enable data streaming. See also the service equivalent (simRosGetObjectParent) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32: the handle of the parent object, or -1 if the object has no parent
|
streamCmd: simros_strmcmd_get_object_pose
Description
|
Enables streaming of an object's pose. See here for information on how to enable data streaming. See also the service equivalent (simRosGetObjectPose) for details. See also simros_strmcmd_set_object_pose. |
Enabling parameters |
auxInt2: a value indicating relative to which reference frame we want the pose. Specify -1 to retrieve the absolute pose, sim_handle_parent to retrieve the pose relative to the object's parent, or an object handle relative to whose reference frame you want the pose
auxString: (not used)
|
Streamed data
|
geometry_msgs::PoseStamped: the pose data. Refer to the ROS documentation
|
streamCmd: simros_strmcmd_get_objects
Description
|
Enables streaming of object handles in the scene, according to their type. See here for information on how to enable data streaming. See also the service equivalent (simRosGetObjects) for details. |
Enabling parameters |
auxInt1: the desired object type (sim_object_shape_type, sim_object_joint_type, etc., or sim_handle_all for any type of object
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32MultiArray: the desired object handles
|
streamCmd: simros_strmcmd_get_object_selection
Description
|
Enables streaming of selected object handles (i.e. handles of object that are in a selected state in the scene). See here for information on how to enable data streaming. See also the service equivalent (simRosGetObjectSelection) for details. See also simros_strmcmd_set_object_selection. |
Enabling parameters |
auxInt1: (not used)
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32MultiArray: the handles of selected objects
|
streamCmd: simros_strmcmd_get_range_finder_data
Description
|
Enables streaming of range finder data (point cloud data). See here for information on how to enable data streaming. |
Enabling parameters |
auxInt1: the handle of an object representing the sensor (doesn't need to be a sensor). See also simRosGetObjectHandle.
auxInt2: (not used)
auxString: name of the string signal that contains point data. Refer also to simSetStringSignal. The string signal should contain a succession of points, where each point contains 3 coordinates (x, y and z). Each coordinate is a float (4 chars). From an embedded script, you can use following construction:
-- example for 3 points:
local points={pt1x,pt1y,pt1z,pt2x,pt2y,pt2z,pt3x,pt3y,pt3z}
local signalData=simPackFloats(points)
simSetStringSignal(signalName,signalData)
|
Streamed data
|
sensor_msgs::PointCloud2: the point cloud data
|
streamCmd: simros_strmcmd_get_string_parameter
Description
|
Enables streaming of a string parameter. See here for information on how to enable data streaming. See also the service equivalent (simRosGetStringParameter) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::String: the desired parameter value
|
streamCmd: simros_strmcmd_get_string_signal
Description
|
Enables streaming of a string signal. See here for information on how to enable data streaming. See also the service equivalent (simRosGetStringSignal) for details. See also simros_strmcmd_set_string_signal. |
Enabling parameters |
auxInt1: (not used)
auxInt2: (not used)
auxString: signal name
|
Streamed data
|
std_msgs::String: the desired signal value
|
streamCmd: simros_strmcmd_get_transform
Description
|
Enables a tf broadcaster, that lets the user keep track of multiple coordinate frames over time. See here for information on how to enable data streaming. |
Enabling parameters |
auxInt2: a value indicating relative to which reference frame we want the transform. Specify -1 to retrieve the absolute transform, sim_handle_parent to retrieve the transform relative to the object's parent, or an object handle relative to whose reference frame you want the transform
auxString: can be an empty string, or can be used to specify the names, in case the objects do not correspond to the exact names we want to use in frame_ids. Syntax is: child_name%parent_name
|
Streamed data
|
geometry_msgs::TransformStamped: the transform
|
streamCmd: simros_strmcmd_get_twist_status
Description
|
Enables streaming of twist data. See here for information on how to enable data streaming. See also simros_strmcmd_set_twist_command. |
Enabling parameters |
auxInt2: (not used)
auxString: name of the string signal that contains the twist data to stream. Refer also to simSetStringSignal. The string signal should contain a succession of 6 float values (6*4 chars). From an embedded script, you can use following construction:
local twist={a,b,c,d,e,f}
local signalData=simPackFloats(twist)
simSetStringSignal(signalName,signalData)
|
Streamed data
|
geometry_msgs::TwistStamped: the twist data
|
streamCmd: simros_strmcmd_get_ui_button_property
Description
|
Enables streaming of a UI button's property (e.g. down/up state, etc.). See here for information on how to enable data streaming. See also the service equivalent (simRosGetUIButtonProperty) for details. See also simros_strmcmd_set_ui_button_property. |
Enabling parameters |
auxInt2: the button ID
auxString: (not used)
|
Streamed data
|
std_msgs::Int32: the desired property value
|
streamCmd: simros_strmcmd_get_ui_event_button
Description
|
Enables streaming of events that occured in a specific UI. Data is only streamed if an event occured. See here for information on how to enable data streaming. See also the service equivalent (simRosGetUIEventButton) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32MultiArray: 3 values:
value1: button ID of the UI button where an event occured
value3: for sliders: slider state (0-1000), for stay down buttons: down state (0 or 1), for up/down event buttons: up/down events (0 or 1)
|
streamCmd: simros_strmcmd_get_ui_slider
Description
|
Enables streaming of the position of a UI slider button. See here for information on how to enable data streaming. See also the service equivalent (simRosGetUISlider) for details. See also simros_strmcmd_set_ui_slider. |
Enabling parameters |
auxInt2: the button ID
auxString: (not used)
|
Streamed data
|
std_msgs::Int32: the slider position (value between 0 and 1000)
|
streamCmd: simros_strmcmd_get_vision_sensor_depth_buffer
Description
|
Enables streaming of the depth buffer values of a vision sensor. See here for information on how to enable data streaming. See also the service equivalent (simRosGetVisionSensorDepthBuffer) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
vrep_common::VisionSensorDepthBuff::x (Int32): the sensor's x-resolution
vrep_common::VisionSensorDepthBuff::y (Int32): the sensor's y-resolution
vrep_common::VisionSensorDepthBuff::data (Float32MultiArray): the depth values. Values are in the range of 0-1 (0=closest to sensor, 1=farthest from sensor).
|
streamCmd: simros_strmcmd_get_vision_sensor_image
Description
|
Enables streaming of the image of a vision sensor. See here for information on how to enable data streaming. See also the service equivalent (simRosGetVisionSensorImage) for details. See also simros_strmcmd_set_vision_sensor_image. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
sensor_msgs::Image: the image data. Refer to the ROS documentation for details
|
streamCmd: simros_strmcmd_get_vision_sensor_info
Description
|
Enables streaming of camera information of a vision sensor. See here for information on how to enable data streaming. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
sensor_msgs::CameraInfo: the camera info
|
streamCmd: simros_strmcmd_read_collision
Description
|
Enables streaming of the collision state of a collision object. See here for information on how to enable data streaming. See also the service equivalent (simRosReadCollision) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Int32: the collision state
|
streamCmd: simros_strmcmd_read_distance
Description
|
Enables streaming of the distance a distance object measured. See here for information on how to enable data streaming. See also the service equivalent (simRosReadDistance) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
std_msgs::Float32: the measured distance
|
streamCmd: simros_strmcmd_read_force_sensor
Description
|
Enables streaming of a force sensor's data (force and torque). See here for information on how to enable data streaming. See also the service equivalent (simRosReadForceSensor) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
vrep_common::ForceSensorData::sensorState (Int32): a bit-coded value:
bit 0 set: force and torque data is available, otherwise it is not (yet) available (e.g. when not enough values are present for the filter)
bit 1 set: force sensor is broken, otherwise it is still intact ('unbroken')
vrep_common::ForceSensorData::force (geometry_msgs/Vector3): the force
vrep_common::ForceSensorData::torque (geometry_msgs/Vector3): the torque
|
streamCmd: simros_strmcmd_read_proximity_sensor
Description
|
Enables streaming of a proximity sensor's data. Data is only streamed when the sensor detects something. See here for information on how to enable data streaming. See also the service equivalent (simRosReadProximitySensor) for details. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
vrep_common::ProximitySensorData::detectedPoint (geometry_msgs::Point32): the detected point. Relative to the sensor reference frame.
vrep_common::ProximitySensorData::detectedObject (Int32): the handle of the detected object
vrep_common::ProximitySensorData::normalVector (geometry_msgs::Point32): the normal vector (normalized) of the detected surface. Relative to the sensor reference frame.
|
streamCmd: simros_strmcmd_read_vision_sensor
Description
|
Enables streaming of a vision sensor's state. See here for information on how to enable data streaming. See also the service equivalent (simRosReadVisionSensor) for details. See also simros_strmcmd_get_vision_sensor_image. |
Enabling parameters |
auxInt2: (not used)
auxString: (not used)
|
Streamed data
|
vrep_common::VisionSensorData::triggerState (Int32): the detection or trigger state.
vrep_common::VisionSensorData::packetData (Float32MultiArray): auxiliary values returned from the applied filters. By default V-REP returns one packet of 15 auxiliary values:the minimum of {intensity, red, green, blue, depth value}, the maximum of {intensity, red, green, blue, depth value}, and the average of {intensity, red, green, blue, depth value}. If additional filter components return values, then they will be appended as packets to the first packet.
vrep_common::VisionSensorData::packetSizes (Int32MultiArray): contains information about the packet sizes. The first value is the size of packet 1, the second value the size of packet 2, etc.
|
|