Hauptinhalt

Blank Message

Create blank message using specified message type

  • Blank Message block

Libraries:
ROS Toolbox / ROS

Description

The Blank Message block creates a Simulink® nonvirtual bus corresponding to the selected ROS message type. The block creates ROS message buses that work with Publish, Subscribe, or Call Service blocks. On each sample hit, the block outputs a blank or “zero” signal for the designated message type. All elements of the bus are initialized to 0. The lengths of the variable-length arrays are also initialized to 0.

Examples

Limitations

Before R2016b, models using ROS message types with certain reserved property names could not generate code. In 2016b, this limitation has been removed. The property names are now appended with an underscore (e.g. Vector3Stamped_). If you use models created with a pre-R2016b release, update the ROS message types using the new names with an underscore. Redefine custom maximum sizes for variable length arrays.

The affected message types are:

  • 'geometry_msgs/Vector3Stamped'

  • 'jsk_pcl_ros/TransformScreenpointResponse'

  • 'pddl_msgs/PDDLAction'

  • 'rocon_interaction_msgs/Interaction'

  • 'capabilities/GetRemappingsResponse'

  • 'dynamic_reconfigure/Group'

Ports

Output

expand all

Blank ROS message, returned as a nonvirtual bus. To specify the type of ROS message, use the Type parameter. All elements of the bus are initialized to 0. The lengths of the variable-length arrays are also initialized to 0.

Data Types: bus

Parameters

expand all

Class of ROS message, specified as Message, Service Request, or Service Response. For basic publishing and subscribing, use the Message class.

ROS message type, specified as a character vector or a dialog box selection. Use Select to select from a list of supported ROS messages. The list of messages given depends on the Class of message you select.

Interval between outputs, specified as a numeric scalar. The default value indicates that the block output never changes. Using this value speeds simulation by eliminating the need to recompute the block output. Otherwise, the block outputs a new blank message at each interval of Sample time.

For more information, see Specify Sample Time (Simulink).

Extended Capabilities

expand all

C/C++ Code Generation
Generate C and C++ code using Simulink® Coder™.

Version History

Introduced in R2019b