주요 콘텐츠

MATLAB Programming for Code Generation

This example shows the recommended workflow for generating a standalone executable from MATLAB® code that contains ROS interfaces.

Prerequisites

  • This example requires MATLAB Coder™.

  • You must have access to a C/C++ compiler that is configured properly. You can use mex -setup cpp to view and change the default compiler. For more details, see Change Default Compiler.

Overview

A subset of ROS MATLAB functions such as rossubscriber, rospublisher, and rosrate support C++ code generation. To create a standalone ROS node from MATLAB code, follow these steps:

  • Create the entry-point function for creating a standalone application. The entry-point function must not have any inputs and must not return any outputs.

  • Add the %#codegen directive to the MATLAB function to indicate that it is intended for code generation. This directive also enables the MATLAB code analyzer to identify warnings and errors specific to MATLAB for code generation.

  • Modify the ROS functions to use message structures.

  • Identify MATLAB code that does not support C++ code generation and modify the MATLAB code to use functions or constructs that support code generation.

  • Create a MATLAB Coder configuration object and specify the hardware as 'Robot Operating System (ROS)'.

  • Use codegen command to generate a stand-alone executable.

Generate Code for Subscriber

Consider the following MATLAB code.

function mynode(numIterations)
%mynode Receive and display sensor_msgs/JointState messages
rosinit;

% Trajectory points to be published
sub = rossubscriber("/servo");

% Display position 
for k = 1:numIterations
    msg = receive(sub);
    if ~isempty(msg.Position > 0)
        disp(msg.Position(1))
    else
        disp("Received empty message..");
    end
end
rosshutdown;
end

This MATLAB code receives sensor_msgs/JointState messages published to the /servo topic and displays the first element of the position in a loop. The function has an input argument that sets the number of iterations. To create a stand-alone ROS node, modify the code as follows:

  • Eliminate the input argument numIterations using a while loop.

  • Add the %#codegen directive.

  • Specify the message type for the rossubscriber call.

  • Use message structures instead of message classes.

  • Eliminate rosinit and rosshutdown calls that do not generate code.

  • Replace the disp function which does not support code generation, with fprintf.

Note that you execute the rosinit and rosshutdown functions only once in a MATLAB session. Avoid rosinit and rosshutdown functions for code intended for standalone deployment. In stand-alone deployment, individual ROS nodes are not expected to start or stop the ROS master. If you need to include rosinit and roshutdown calls in your MATLAB code for interpreted execution, declare them as coder.extrinsic (MATLAB Coder) functions at the top of your entry-point function.

The entry-point function cannot take any inputs or return outputs. A standalone ROS node executable is intended to be launched outside MATLAB, such as from a system command terminal, and therefore cannot take any MATLAB inputs or return MATLAB outputs.

To eliminate the input argument numIterations, replace the for loop with an infinite while loop. For stand-alone deployment, the generated node is expected to run until you terminate it externally. A good programming practice is to replace the for loops with a while loop for standalone deployment.

The rossubscriber function needs the message type to be specified as a compile time constant for code generation. The function uses this information to create the return message type for receive calls. The rossubscriber function supports code generation for message structures only. To return a message structure, specify the name-value pair argument, "DataFormat","struct", when creating a subscriber.

After you modify the code, the MATLAB code for the entry-point function is as follows:

function mynode
%mynode Receive and display sensor_msgs/JointState messages
%#codegen

% Trajectory points to publish
sub = rossubscriber("/servo","sensor_msgs/JointState","DataFormat","struct");

% Display position 
while (1) 
    msg = receive(sub);
    if ~isempty(msg.Position > 0)
        fprintf("Position = %f\n",msg.Position(1))
    else
        fprintf("Received empty message..\n");
    end
end
end

Create a MATLAB Coder configuration that uses "Robot Operating System (ROS)" hardware. Set the HardwareImplementation.ProdHWDeviceType parameter of the MATLAB Coder configuration object for the intended deployment hardware. For example, if you are deploying generated code to a Windows computer set HardwareImplementation.ProdHWDeviceType to "Intel->x86-64 (Windows64)". To generate code, execute the following commands:

cfg = coder.config("exe");
cfg.Hardware = coder.hardware("Robot Operating System (ROS)");
cfg.Hardware.DeployTo = "Localhost"; 
cfg.Hardware.BuildAction = "Build and run";
cfg.HardwareImplementation.ProdHWDeviceType = "Intel->x86-64 (Windows64)";
cfg.HardwareImplementation.ProdLongLongMode = true; % Use 'long long' for Int64 or Uint64 data types
codegen mynode -config cfg

You can send messages to mynode using the following command on a ROS terminal:

rostopic pub /servo sensor_msgs/JointState -r 1 "{header:{seq: 0, stamp:{secs: 0,nsecs: 0},frame_id:""},name:["joint"],position:[150.0,100.0],velocity:[0.0,0.0],effort:[0,0]}"

Generate Code for Publisher

Consider the following MATLAB code.

function mypubnode(updateRate)
%mypubnode Publish joint trajectory messages

% Create publisher 
pub = rospublisher("/traj","trajectory_msgs/JointTrajectory");

% Create a message 
msg = rosmessage("trajectory_msgs/JointTrajectory");
msg.JointNames{1} = 'Left';
msg.JointNames{2} = 'Right';
trajMsg = rosmessage("trajectory_msgs/JointTrajectoryPoint");
r = rosrate(updateRate);
while (1)
    msg.Header.Stamp = rostime("now");
    x = rand;
    y = rand;
    trajMsg.Positions = [x y -x -y];
    msg.Points = [trajMsg trajMsg];
    send(pub,msg);
    waitfor(r);
end
end

This MATLAB code publishes trajectory_msgs/JointTrajectory messages to the /traj topic. You can set the message publishing rate externally. The trajectory_msgs/JointTrajectory message is a nested message that has the following subfields:

>> rosmsg show trajectory_msgs/JointTrajectory
std_msgs/Header Header
char[] JointNames
JointTrajectoryPoint[] Points

The message can accommodate multiple joints and multiple trajectory points. If the number of joints is M and the number of trajectory points for each joint is N, trajMsg has the dimensions M-by-1 and trajMsg.Positions has the dimensions N-by-1. For this example, publish two trajectory points per joint.

The function has an input argument that sets the number of iterations. To create a stand-alone ROS node, modify the code as follows:

  • Eliminate the input argument updateRate by directly specifying it within function body.

  • Add the %#codegen directive.

  • Use message structures instead of message classes.

  • Eliminate any message fields that use cell strings to prepare for code generation.

  • Grow variable-size fields of message structures in the correct dimension.

To eliminate the input argument updateRate, specify the update rate using a constant literal in the entry-point function body. To modify the updateRate, you must re-generate code from the entry-point function.

Modify the rospublisher, rosmessage and rosrate functions to use message structures. The trajectory_msgs/JointTrajectory message structure has a field, JointNames, which is of type cell string. Message fields of this type are not supported for code generation due to MATLAB Coder limitations. In order to generate code for mypubnode function, avoid the use of JointNames fields in code generation using coder.target (MATLAB Coder) function.

The original mypubnode function grows variable-size fields of the message structs in the wrong dimension. As an illustration, create a message of type trajectory_msgs/JointTrajectory at the MATLAB command line. Note that the first dimension of the variable-size fields is of size 0 while the second dimension is of size 1:

msg = rosmessage('trajectory_msgs/JointTrajectory')

msg = 

  ROS JointTrajectory message with properties:

    MessageType: 'trajectory_msgs/JointTrajectory'
         Header: [1×1 Header]
         Points: [0×1 JointTrajectoryPoint]
     JointNames: {0×1 cell}

  Use showdetails to show the contents of the message

The fields with dimensions 0-by-1 grow in the first dimension. The original code grows the Points and Positions fields in the second dimension, which works in interpreted mode, but is not supported for code generation. You get the following error message if you attempt to grow variable-size fields of a message structure in the wrong dimension:

??? Attempt to write a value of type 'trajectory_msgs_JointTrajectoryPointStruct_T' into a variable defined as type 'struct_T'. 
Code generation does not support changing types through assignment. 
To investigate the cause of the type mismatch, check preceding assignments or input type specifications.

After you modify the code, the MATLAB code for the entry-point function is as follows:

function mypubnode
%mypubnode Publish joint trajectory messages
%#codegen

% Create publisher 
pub = rospublisher("/traj","trajectory_msgs/JointTrajectory","DataFormat","struct");

% Create a msg 
msg = rosmessage("trajectory_msgs/JointTrajectory","DataFormat","struct");
if isempty(coder.target)
    msg.JointNames{1} = 'Left';
    msg.JointNames{2} = 'Right';
end
trajMsg = rosmessage("trajectory_msgs/JointTrajectoryPoint","DataFormat","struct");
r = rosrate(1);
while (1)
    msg.Header.Stamp = rostime("now","DataFormat","struct");
    x = rand;
    y = rand;
    trajMsg.Positions = [x; y; -x; -y]; % Grow variable-size fields in the correct dimension
    msg.Points = [trajMsg; trajMsg];    % Grow variable-size fields in the correct dimension
    send(pub,msg);
    waitfor(r);
end
end

Create a MATLAB Coder configuration that uses "Robot Operating System (ROS)" hardware. Set the HardwareImplementation.ProdHWDeviceType parameter of the MATLAB Coder configuration object for the intended deployment hardware. For example, if you are deploying generated code to a Windows computer set HardwareImplementation.ProdHWDeviceType to "Intel->x86-64 (Windows64)". To generate code execute the following commands:

cfg = coder.config("exe");
cfg.Hardware = coder.hardware("Robot Operating System (ROS)");
cfg.Hardware.DeployTo = "Localhost";
cfg.Hardware.BuildAction = "Build and run";
cfg.HardwareImplementation.ProdHWDeviceType = "Intel->x86-64 (Windows64)";
cfg.HardwareImplementation.ProdLongLongMode = true; % Use 'long long' for Int64 or Uint64 data types
codegen mypubnode -config cfg

You can examine the contents of the messages published by mypubnode using rostopic echo /traj command on a ROS terminal.

Additional Considerations

Code generation for messages containing cell strings: MATLAB Coder does not support code generation for cell strings. You can send and receive ROS messages containing cell strings using rossubsriber and rospublisher, but you cannot access the fields that are of type cell string. For instance, in a sensor_msgs/JointState message, you cannot read or write to the field, Name, which is of type cell string in MATLAB representation.

Variable-size message fields: Do not use indexing past the array dimension pattern to grow the size of variable-size arrays in message fields. Use the following form:

msg = rosmessage('sensor_msgs/JointState','DataFormat','struct');
msg.Position = [0.1; -0.1];
...
msg.Position = [msg.Position; 0.2]; % Add new data point

For more information, see Incompatibilities with MATLAB in Variable-Size Support for Code Generation (MATLAB Coder). Also, for the MATLAB Coder configuration object, you must set EnableVariableSizing property to true and enable dynamic memory allocation for variable-size arrays.

See Also

Topics