Main Content

Generate a Standalone ROS Node

This example shows how to generate C++ code for a standalone ROS node from a MATLAB function. It then shows how to build and run the ROS node on a Windows® machine.

Prerequisites

  • This example requires MATLAB Coder™.

  • A Ubuntu Linux system with ROS and an SSH server installed is necessary for building and running the generated C++ code. You can use your own Ubuntu ROS system, or you can use the Linux virtual machine for ROS Toolbox examples (see Get Started with Gazebo and Simulated TurtleBot for instructions).

  • 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.

Control a ROS-Enabled Robot with a Function

Open the function robotROSFeedbackControl, which contains a proportional controller introduced in the Feedback Control of a ROS-Enabled Robot example. This function subscribes to the /odom topic to get the current odometry status of the robot, and then publishes the output of a proportional controller as a geometry_msgs/Twist message to the /cmd_vel topic. Doing so provides the control commands for the robot to move towards the desired position.

Copy the robotROSFeedbackControl function to your local directory and change the defaultDesiredPos variable to the desired coordinates.

Start an a Gazebo Empty World from the Linux virtual machine by opening the Gazebo Empty application on the desktop. In the Linux virtual machine for ROS Toolbox, the robot is located at the [0,0] location by default.

Create a rosdevice object specifying the deviceAddress, username, and password values of the Virtual Machine running Gazebo. This establishes an SSH connection between the ROS device and MATLAB.

gazeboVMDevice = rosdevice('172.18.250.139','user','password');

Create a MATLAB ROS node in the same ROS network as the virtual machine. See the list of available ROS nodes.

rosinit(gazeboVMDevice.DeviceAddress,11311)
Initializing global node /matlab_global_node_38424 with NodeURI http://172.18.250.141:65043/ and MasterURI http://172.18.250.139:11311.
rosnode list
/gazebo
/gazebo_gui
/matlab_global_node_38424
/rosout

Run the controller and observe that the robot is moving towards the published destination. At the same time, observe the trajectory of the robot that shows up in a MATLAB figure. Keep this figure open to compare the behavior of MATLAB execution and the generated executable node.

robotROSFeedbackControl

You can change the desired destination while the robot is moving. To do so, open a new terminal from the virtual machine, source the ROS repository, and publish the new destination coordinates in the form of a std_msgs/Float64MultiArray message to the /dest topic.

~$ source /opt/ros/noetic/local_setup.bash
~$ rostopic pub -1 /dest std_msgs/Float64MultiArray "{data:[0,0]}"  

You can also tweak the distanceThre, linearVelocity, and rotationGain values in robotROSFeedbackControl.m to obtain the desired robot behavior. For the proportional controller in this example, the following parameter ranges provide robust performance. Alternatively, you can replace the proportional controller with a custom controller for performance comparison. To observe the behavior, reset the robot on the virtual machine by pressing Ctrl-R in Gazebo.

distanceThre: 0<x<1
linearVelocity: 0<x<3
rotationGain: 0<x<6

The controller loop will terminate after the goal is reached, if more than 40 seconds has elapsed since the start time. Alternatively, you can terminate the controller any time using Ctrl-C or typing in the following command in the terminal from the virtual machine. Note that if you open a new terminal in the virtual machine, you must source the ROS repository.

~$ rostopic pub -1 /stop std_msgs/Bool "1"

Create a Function for Code Generation

To generate a standalone C++ node, modify the function to make it compatible for code generation.

  • Because objects do not support code generation, replace them with structs for rospublisher, rossubscriber, and rosmessage. Specify the name-value pair "DataFormat","struct" in the respective function calls to create them as structures.

  • Save the modified MATLAB function to robotROSFeedbackControlCodegen.m. Ensure any other modifications that you made in robotROSFeedbackControl function are reflected in robotROSFeedbackControlCodegen.

Generate Executable for robotROSFeedbackControlCodegen

Reset the Gazebo scene after simulation using the /gazebo/reset_simulation service. Create a rossvcclient object for the service and use the call object function to call the service and reset the Gazebo simulation scene.

gazeboResetClient = rossvcclient('/gazebo/reset_simulation','DataFormat','struct');
call(gazeboResetClient);

Generate an executable node for the robotROSFeedbackControlCodegen function. Specify the hardware as 'Robot Operating System (ROS)'. Set the build action to Build and run so that the ROS node starts running after you generate it. Specify the coder configuration parameters for remote deployment. This example specifies the remote device parameters of the virtual machine running Gazebo. Note that the actual values might be different for your remote device. Verify them before deployment.

cfg = coder.config('exe');
cfg.Hardware = coder.hardware('Robot Operating System (ROS)');
cfg.Hardware.BuildAction = 'Build and run';
cfg.Hardware.RemoteDeviceAddress = '172.18.250.139';
cfg.Hardware.RemoteDeviceUsername = 'user';
cfg.Hardware.RemoteDevicePassword = 'password';
cfg.Hardware.DeployTo = 'Remote Device';
codegen robotROSFeedbackControlCodegen -args {} -config cfg
Connecting to ROS device '172.18.250.139'.
Using Catkin workspace '~/catkin_ws' to build ROS node.
---
Transferring generated code for 'robotROSFeedbackControlCodegen' to ROS device.
Starting build for ROS node.
---
tar: Ignoring unknown extended header keyword 'SCHILY.fflags'
Catkin project directory: /home/user/catkin_ws/src/robotrosfeedbackcontrolcodegen
tar: Ignoring unknown extended header keyword 'SCHILY.fflags'
tar: Ignoring unknown extended header keyword 'SCHILY.fflags'
tar: Ignoring unknown extended header keyword 'SCHILY.fflags'
-- Using CATKIN_DEVEL_PREFIX: /home/user/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /home/user/catkin_ws/devel;/opt/ros/noetic
-- This workspace overlays: /home/user/catkin_ws/devel;/opt/ros/noetic
-- Found PythonInterp: /usr/bin/python3 (found suitable version "3.8.10", minimum required is "3") 
-- Using PYTHON_EXECUTABLE: /usr/bin/python3
-- Using Debian Python package layout
-- Using empy: /usr/lib/python3/dist-packages/em.py
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/user/catkin_ws/build/test_results


-- Forcing gtest/gmock from source, though one was otherwise available.
-- Found gtest sources under '/usr/src/googletest': gtests will be built
-- Found gmock sources under '/usr/src/googletest': gmock will be built
-- Found PythonInterp: /usr/bin/python3 (found version "3.8.10") 
-- Using Python nosetests: /usr/bin/nosetests3
-- catkin 0.8.10
-- BUILD_SHARED_LIBS is on
-- BUILD_SHARED_LIBS is on

-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~  traversing 41 packages in topological order:
-- ~~  - husky_desktop (metapackage)
-- ~~  - husky_simulator (metapackage)
-- ~~  - kortex_move_it_config (metapackage)
-- ~~  - mav_comm (metapackage)
-- ~~  - rotors_description
-- ~~  - rotors_simulator (metapackage)
-- ~~  - husky_msgs
-- ~~  - mav_state_machine_msgs
-- ~~  - mav_system_msgs
-- ~~  - rotors_comm
-- ~~  - mav_msgs
-- ~~  - robotrosfeedbackcontrolcodegen
-- ~~  - husky_control
-- ~~  - husky_description
-- ~~  - husky_gazebo
-- ~~  - husky_navigation
-- ~~  - husky_viz
-- ~~  - kortex_control
-- ~~  - kortex_description
-- ~~  - kortex_gazebo
-- ~~  - rotors_evaluation
-- ~~  - rqt_rotors
-- ~~  - mav_planning_msgs
-- ~~  - opencv_node
-- ~~  - rotors_control
-- ~~  - rotors_hil_interface
-- ~~  - rotors_joy_interface
-- ~~  - gazebo_version_helpers
-- ~~  - gazebo_grasp_plugin
-- ~~  - roboticsgroup_upatras_gazebo_plugins
-- ~~  - rotors_gazebo_plugins
-- ~~  - kortex_driver
-- ~~  - gen3_lite_gen3_lite_2f_move_it_config
-- ~~  - gen3_move_it_config
-- ~~  - gen3_robotiq_2f_140_move_it_config
-- ~~  - gen3_robotiq_2f_85_move_it_config
-- ~~  - kortex_examples
-- ~~  - kortex_gazebo_camera
-- ~~  - kortex_gazebo_depth
-- ~~  - rotors_gazebo
-- ~~  - mw_vision_example
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin metapackage: 'husky_desktop'
-- ==> add_subdirectory(husky/husky_desktop)
-- +++ processing catkin metapackage: 'husky_simulator'
-- ==> add_subdirectory(husky/husky_simulator)
-- +++ processing catkin metapackage: 'kortex_move_it_config'
-- ==> add_subdirectory(ros_kortex/kortex_move_it_config/kortex_move_it_config)
-- +++ processing catkin metapackage: 'mav_comm'
-- ==> add_subdirectory(mav_comm/mav_comm)
-- +++ processing catkin package: 'rotors_description'
-- ==> add_subdirectory(rotors_simulator/rotors_description)

-- +++ processing catkin metapackage: 'rotors_simulator'
-- ==> add_subdirectory(rotors_simulator/rotors_simulator)
-- +++ processing catkin package: 'husky_msgs'
-- ==> add_subdirectory(husky/husky_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- husky_msgs: 1 messages, 0 services
-- +++ processing catkin package: 'mav_state_machine_msgs'
-- ==> add_subdirectory(mav_comm/mav_state_machine_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- mav_state_machine_msgs: 1 messages, 1 services

-- +++ processing catkin package: 'mav_system_msgs'
-- ==> add_subdirectory(mav_comm/mav_system_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- mav_system_msgs: 2 messages, 0 services
-- +++ processing catkin package: 'rotors_comm'
-- ==> add_subdirectory(rotors_simulator/rotors_comm)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- rotors_comm: 1 messages, 2 services

-- +++ processing catkin package: 'mav_msgs'
-- ==> add_subdirectory(mav_comm/mav_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- mav_msgs: 8 messages, 0 services
-- +++ processing catkin package: 'robotrosfeedbackcontrolcodegen'
-- ==> add_subdirectory(robotrosfeedbackcontrolcodegen)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- +++ processing catkin package: 'husky_control'
-- ==> add_subdirectory(husky/husky_control)
-- +++ processing catkin package: 'husky_description'
-- ==> add_subdirectory(husky/husky_description)
-- +++ processing catkin package: 'husky_gazebo'
-- ==> add_subdirectory(husky/husky_gazebo)
-- +++ processing catkin package: 'husky_navigation'
-- ==> add_subdirectory(husky/husky_navigation)
-- +++ processing catkin package: 'husky_viz'
-- ==> add_subdirectory(husky/husky_viz)

-- +++ processing catkin package: 'kortex_control'
-- ==> add_subdirectory(ros_kortex/kortex_control)
-- +++ processing catkin package: 'kortex_description'
-- ==> add_subdirectory(ros_kortex/kortex_description)
-- +++ processing catkin package: 'kortex_gazebo'
-- ==> add_subdirectory(ros_kortex/kortex_gazebo)
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
-- Looking for ignition-math6 -- found version 6.8.0
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8

-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0

-- +++ processing catkin package: 'rotors_evaluation'
-- ==> add_subdirectory(rotors_simulator/rotors_evaluation)
-- Installing devel-space wrapper /home/user/catkin_ws/src/rotors_simulator/rotors_evaluation/src/disturbance_eval.py to /home/user/catkin_ws/devel/lib/rotors_evaluation
-- Installing devel-space wrapper /home/user/catkin_ws/src/rotors_simulator/rotors_evaluation/src/hovering_eval.py to /home/user/catkin_ws/devel/lib/rotors_evaluation
-- Installing devel-space wrapper /home/user/catkin_ws/src/rotors_simulator/rotors_evaluation/src/waypoints_eval.py to /home/user/catkin_ws/devel/lib/rotors_evaluation
-- +++ processing catkin package: 'rqt_rotors'
-- ==> add_subdirectory(rotors_simulator/rqt_rotors)
-- mavros_msgs not found, skipping rqt_rotors package.

-- +++ processing catkin package: 'mav_planning_msgs'
-- ==> add_subdirectory(mav_comm/mav_planning_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- mav_planning_msgs: 9 messages, 3 services
-- +++ processing catkin package: 'opencv_node'
-- ==> add_subdirectory(opencv_node)

-- +++ processing catkin package: 'rotors_control'
-- ==> add_subdirectory(rotors_simulator/rotors_control)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
CMake Warning at /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:166 (message):
  catkin_package() DEPENDS on 'Eigen3' but neither 'Eigen3_INCLUDE_DIRS' nor
  'Eigen3_LIBRARIES' is defined.
Call Stack (most recent call first):
  /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
  rotors_simulator/rotors_control/CMakeLists.txt:17 (catkin_package)


-- +++ processing catkin package: 'rotors_hil_interface'
-- ==> add_subdirectory(rotors_simulator/rotors_hil_interface)
-- Mavlink not found. Skipping HIL_INTERFACE package.
-- +++ processing catkin package: 'rotors_joy_interface'
-- ==> add_subdirectory(rotors_simulator/rotors_joy_interface)

-- +++ processing catkin package: 'gazebo_version_helpers'
-- ==> add_subdirectory(ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
-- Looking for ignition-math6 -- found version 6.8.0
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 

-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0
CMake Warning at /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:166 (message):
  catkin_package() DEPENDS on 'gazebo' but neither 'gazebo_INCLUDE_DIRS' nor
  'gazebo_LIBRARIES' is defined.
Call Stack (most recent call first):
  /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
  ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt:26 (catkin_package)



-- +++ processing catkin package: 'gazebo_grasp_plugin'
-- ==> add_subdirectory(ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
-- Looking for ignition-math6 -- found version 6.8.0
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0

-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0
CMake Warning at /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:166 (message):
  catkin_package() DEPENDS on 'gazebo' but neither 'gazebo_INCLUDE_DIRS' nor
  'gazebo_LIBRARIES' is defined.
Call Stack (most recent call first):
  /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
  ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt:31 (catkin_package)


-- +++ processing catkin package: 'roboticsgroup_upatras_gazebo_plugins'
-- ==> add_subdirectory(ros_kortex/third_party/roboticsgroup_upatras_gazebo_plugins)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
-- Looking for ignition-math6 -- found version 6.8.0
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'

--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0
-- +++ processing catkin package: 'rotors_gazebo_plugins'
-- ==> add_subdirectory(rotors_simulator/rotors_gazebo_plugins)
-- BUILD_OCTOMAP_PLUGIN variable not provided, setting to FALSE.
-- BUILD_OPTICAL_FLOW_PLUGIN variable not provided, setting to FALSE.
-- NO_ROS variable not provided, setting to FALSE.
-- CMAKE_BINARY_DIR = /home/user/catkin_ws/build

-- Could NOT find MAVLink (missing: MAVLINK_INCLUDE_DIRS) (found version "2.0")
--  mavlink not found, not building MAVLINK_INTERFACE_PLUGIN.
-- ADDITIONAL_INCLUDE_DIRS = 
-- BUILD_OCTOMAP_PLUGIN = FALSE, NOT building gazebo_octomap_plugin.
-- BUILD_OPTICAL_FLOW_PLUGIN = FALSE, NOT building gazebo_optical_flow_plugin.
-- NO_ROS = FALSE, building rotors_gazebo_plugins WITH ROS dependancies.
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- CMAKE_BINARY_DIR = /home/user/catkin_ws/build
-- Eigen found (include: /usr/include/eigen3)
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
-- Looking for ignition-math6 -- found version 6.8.0

-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2

-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Gazebo version: 11.5
-- No yaml_cpp_catkin, using yaml-cpp system library instead.
-- PROTOBUF_IMPORT_DIRS = /usr/include/gazebo-11/gazebo/msgs/proto
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1") 
CMake Warning at /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:166 (message):
  catkin_package() DEPENDS on 'octomap' but neither 'octomap_INCLUDE_DIRS'
  nor 'octomap_LIBRARIES' is defined.
Call Stack (most recent call first):
  /opt/ros/noetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
  rotors_simulator/rotors_gazebo_plugins/CMakeLists.txt:229 (catkin_package)


-- GAZEBO 11.5.1
-- 
-- BUILD_MAVLINK_INTERFACE_PLUGIN = FALSE, NOT adding mavros dependency and NOT building mavlink_interface_plugin.
-- CMAKE_INSTALL_PREFIX = /home/user/catkin_ws/install
-- +++ processing catkin package: 'kortex_driver'
-- ==> add_subdirectory(ros_kortex/kortex_driver)
CONAN_TARGET_PLATFORM is x86
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found version "1.71.0") found components: system 
-- Generating .msg files for action kortex_driver/FollowCartesianTrajectory /home/user/catkin_ws/src/ros_kortex/kortex_driver/action/non_generated/FollowCartesianTrajectory.action

-- kortex_driver: 432 messages, 259 services

-- Conan: checking conan executable in path
-- Conan: Found program /usr/local/bin/conan

-- Conan: Version found Conan version 1.39.0

-- Conan: Adding kinova_public remote repository (https://artifactory.kinovaapps.com/artifactory/api/conan/conan-public)

-- Conan: Automatic detection of conan settings from cmake
-- Conan: Settings= -s;build_type=Release;-s;compiler=gcc;-s;compiler.version=9;-s;compiler.libcxx=libstdc++11;-s;kortex_api_cpp:compiler=gcc;-s;kortex_api_cpp:compiler.version=5;-s;kortex_api_cpp:compiler.libcxx=libstdc++11
-- Conan executing: conan install /home/user/catkin_ws/src/ros_kortex/kortex_driver/conanfile.py -s build_type=Release -s compiler=gcc -s compiler.version=9 -s compiler.libcxx=libstdc++11 -s kortex_api_cpp:compiler=gcc -s kortex_api_cpp:compiler.version=5 -s kortex_api_cpp:compiler.libcxx=libstdc++11 -g=cmake --update
Configuration:
[settings]
arch=x86_64
arch_build=x86_64
build_type=Release
compiler=gcc
compiler.libcxx=libstdc++11
compiler.version=9
os=Linux
os_build=Linux
kortex_api_cpp:compiler=gcc
kortex_api_cpp:compiler.version=5
kortex_api_cpp:compiler.libcxx=libstdc++11
[options]
[build_requires]
[env]


conanfile.py: Installing package
Requirements
    kortex_api_cpp/2.3.0-r.34@kortex/stable from 'kinova_public' - Cache
Packages
    kortex_api_cpp/2.3.0-r.34@kortex/stable:c023db9fc677d4d0b3bd0c20f71385e4cf8a1220 - Cache

Installing (downloading, building) binaries...
kortex_api_cpp/2.3.0-r.34@kortex/stable: Already installed!
conanfile.py: Generator cmake created conanbuildinfo.cmake
conanfile.py: Generator txt created conanbuildinfo.txt
conanfile.py: Aggregating env generators
conanfile.py: Generated conaninfo.txt
conanfile.py: Generated graphinfo
-- Conan: Loading conanbuildinfo.cmake
-- Conan: Using cmake targets configuration
-- Library KortexApiCpp found /home/user/.conan/data/kortex_api_cpp/2.3.0-r.34/kortex/stable/package/c023db9fc677d4d0b3bd0c20f71385e4cf8a1220/lib/libKortexApiCpp.a
-- Conan: Adjusting default RPATHs Conan policies
-- Conan: Adjusting language standard
-- Current conanbuildinfo.cmake directory: /home/user/catkin_ws/build/ros_kortex/kortex_driver
-- WARN: CONAN_COMPILER variable not set, please make sure yourself that your compiler and version matches your declared settings
-- +++ processing catkin package: 'gen3_lite_gen3_lite_2f_move_it_config'
-- ==> add_subdirectory(ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config)

-- +++ processing catkin package: 'gen3_move_it_config'
-- ==> add_subdirectory(ros_kortex/kortex_move_it_config/gen3_move_it_config)
-- +++ processing catkin package: 'gen3_robotiq_2f_140_move_it_config'
-- ==> add_subdirectory(ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config)
-- +++ processing catkin package: 'gen3_robotiq_2f_85_move_it_config'
-- ==> add_subdirectory(ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config)
-- +++ processing catkin package: 'kortex_examples'
-- ==> add_subdirectory(ros_kortex/kortex_examples)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/full_arm/example_waypoint_action_client.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/move_it/example_move_it_trajectories.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- Installing devel-space wrapper /home/user/catkin_ws/src/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.py to /home/user/catkin_ws/devel/lib/kortex_examples
-- +++ processing catkin package: 'kortex_gazebo_camera'
-- ==> add_subdirectory(kortex_gazebo_camera)
-- +++ processing catkin package: 'kortex_gazebo_depth'
-- ==> add_subdirectory(kortex_gazebo_depth)
-- +++ processing catkin package: 'rotors_gazebo'
-- ==> add_subdirectory(rotors_simulator/rotors_gazebo)
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart 
-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found suitable version "1.71.0", minimum required is "1.40.0") found components: thread system filesystem program_options regex iostreams date_time 
-- Looking for ignition-math6 -- found version 6.8.0
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-transport8 -- found version 8.2.0
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2

-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.8.0
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Looking for ignition-common3 -- found version 3.13.1
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.13.1
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.8.0
-- Looking for ignition-fuel_tools4 -- found version 4.3.0
-- Searching for dependencies of ignition-fuel_tools4
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Looking for ignition-common3 -- found version 3.13.1
-- Looking for ignition-msgs5 -- found version 5.7.0
-- Building iris.sdf.

-- +++ processing catkin package: 'mw_vision_example'
-- ==> add_subdirectory(mw_vision_example)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Configuring done

-- Generating done

-- Build files have been written to: /home/user/catkin_ws/build
cd /home/user/catkin_ws/build && /usr/bin/cmake -S/home/user/catkin_ws/src -B/home/user/catkin_ws/build --check-build-system CMakeFiles/Makefile.cmake 0
cd /home/user/catkin_ws/build && /usr/bin/cmake -E cmake_progress_start /home/user/catkin_ws/build/CMakeFiles /home/user/catkin_ws/build/robotrosfeedbackcontrolcodegen/CMakeFiles/progress.marks
cd /home/user/catkin_ws/build && make -f CMakeFiles/Makefile2 robotrosfeedbackcontrolcodegen/all
make[1]: Entering directory '/home/user/catkin_ws/build'
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target nav_msgs_generate_messages_lisp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target nav_msgs_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target std_msgs_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target std_msgs_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target std_msgs_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target std_msgs_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target std_msgs_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target geometry_msgs_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target geometry_msgs_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target geometry_msgs_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target geometry_msgs_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target geometry_msgs_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target actionlib_msgs_generate_messages_py
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target actionlib_msgs_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target actionlib_msgs_generate_messages_lisp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target actionlib_msgs_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target actionlib_msgs_generate_messages_cpp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target actionlib_msgs_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target nav_msgs_generate_messages_py
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target nav_msgs_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target nav_msgs_generate_messages_nodejs
make[2]: Leaving directory '/home/user/catkin_ws/build'

[  0%] Built target nav_msgs_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target roscpp_generate_messages_eus
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target roscpp_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target rosgraph_msgs_generate_messages_nodejs
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target rosgraph_msgs_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target roscpp_generate_messages_py
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target roscpp_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target roscpp_generate_messages_nodejs
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target roscpp_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target rosgraph_msgs_generate_messages_cpp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target rosgraph_msgs_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target rosgraph_msgs_generate_messages_eus
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target rosgraph_msgs_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target actionlib_msgs_generate_messages_nodejs
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target actionlib_msgs_generate_messages_nodejs
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target rosgraph_msgs_generate_messages_lisp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target rosgraph_msgs_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target actionlib_msgs_generate_messages_eus
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target actionlib_msgs_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target roscpp_generate_messages_lisp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target roscpp_generate_messages_lisp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target rosgraph_msgs_generate_messages_py
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target rosgraph_msgs_generate_messages_py
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target nav_msgs_generate_messages_eus
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target nav_msgs_generate_messages_eus
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target roscpp_generate_messages_cpp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target roscpp_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target nav_msgs_generate_messages_cpp
make[2]: Leaving directory '/home/user/catkin_ws/build'
[  0%] Built target nav_msgs_generate_messages_cpp
make[2]: Entering directory '/home/user/catkin_ws/build'
Scanning dependencies of target robotROSFeedbackControlCodegen
make[2]: Leaving directory '/home/user/catkin_ws/build'
make[2]: Entering directory '/home/user/catkin_ws/build'
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/Publisher.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/Subscriber.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PointStruct.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PoseStruct.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PoseWithCovarianceStruct.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_QuaternionStruct.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_TwistStruct.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_TwistWithCovarianceStruct.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_Vector3Struct.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/main.cpp.o

[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/nav_msgs_OdometryStruct.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/quat2eul.cpp.o
[  0%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen.cpp.o

[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_data.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_initialize.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_terminate.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/ros_TimeStruct.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/ros_structmsg_conversion.cpp.o

[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rtGetInf.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rtGetNaN.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rt_nonfinite.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_BoolStruct.cpp.o

[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_Float64MultiArrayStruct.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_HeaderStruct.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_MultiArrayDimensionStruct.cpp.o

[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_MultiArrayLayoutStruct.cpp.o
[100%] Building CXX object robotrosfeedbackcontrolcodegen/CMakeFiles/robotROSFeedbackControlCodegen.dir/src/mlroscpp_sub.cpp.o

[100%] Linking CXX executable /home/user/catkin_ws/devel/lib/robotrosfeedbackcontrolcodegen/robotROSFeedbackControlCodegen
/usr/bin/c++  -O3 -DNDEBUG   CMakeFiles/robotROSFeedbackControlCodegen.dir/src/Publisher.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/Subscriber.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PointStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PoseStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_PoseWithCovarianceStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_QuaternionStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_TwistStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_TwistWithCovarianceStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/geometry_msgs_Vector3Struct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/main.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/nav_msgs_OdometryStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/quat2eul.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_data.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_initialize.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/robotROSFeedbackControlCodegen_terminate.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/ros_TimeStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/ros_structmsg_conversion.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rtGetInf.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rtGetNaN.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/rt_nonfinite.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_BoolStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_Float64MultiArrayStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_HeaderStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_MultiArrayDimensionStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/std_msgs_MultiArrayLayoutStruct.cpp.o CMakeFiles/robotROSFeedbackControlCodegen.dir/src/mlroscpp_sub.cpp.o  -o /home/user/catkin_ws/devel/lib/robotrosfeedbackcontrolcodegen/robotROSFeedbackControlCodegen  -Wl,-rpath,/home/user/catkin_ws/install/lib:/opt/ros/noetic/lib /opt/ros/noetic/lib/libroscpp.so /usr/lib/x86_64-linux-gnu/libpthread.so /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0 /opt/ros/noetic/lib/librosconsole.so /opt/ros/noetic/lib/librosconsole_log4cxx.so /opt/ros/noetic/lib/librosconsole_backend_interface.so /usr/lib/x86_64-linux-gnu/liblog4cxx.so /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0 /opt/ros/noetic/lib/libxmlrpcpp.so /opt/ros/noetic/lib/libroscpp_serialization.so /opt/ros/noetic/lib/librostime.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0 /opt/ros/noetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4 -ldl 
make[2]: Leaving directory '/home/user/catkin_ws/build'
[100%] Built target robotROSFeedbackControlCodegen
make[1]: Leaving directory '/home/user/catkin_ws/build'
/usr/bin/cmake -E cmake_progress_start /home/user/catkin_ws/build/CMakeFiles 0
Base path: /home/user/catkin_ws
Source space: /home/user/catkin_ws/src
Build space: /home/user/catkin_ws/build
Devel space: /home/user/catkin_ws/devel
Install space: /home/user/catkin_ws/install
####
#### Running command: "cmake /home/user/catkin_ws/src -DCATKIN_DEVEL_PREFIX=/home/user/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/user/catkin_ws/install -G Unix Makefiles" in "/home/user/catkin_ws/build"
####
####
#### Running command: "make -j2 -l2" in "/home/user/catkin_ws/build/robotrosfeedbackcontrolcodegen"
####

---
Running ROS node.
---
The node will connect to the ROS master at 'http://172.18.250.139:11311' and advertise its address as '172.18.250.139'.
Use the 'rosdevice' object to stop the node or restart it with different settings.
Code generation successful.

Reset the Gazebo scene and call plotPath to plot the robot trajectory.

call(gazeboResetClient);
plotPath

The configuration generates and runs the ROS node on your remote device. You can opt to deploy and run the ROS node on the local machine by modifying the coder configuration object, cfg.

cfg = coder.config('exe');
cfg.Hardware = coder.hardware('Robot Operating System (ROS)');
cfg.Hardware.BuildAction = 'Build and run';
cfg.Hardware.DeployTo = 'Localhost';
codegen robotROSFeedbackControlCodegen -args {} -config cfg
plotPath

Verify Generated ROS Node

After the generated executable starts running, for the same destination coordinates, verify that the trajectory of the robot is similar to what you observe during MATLAB execution. You can also observe the robot moving in Gazebo on the virtual machine. You can publish a different destination coordinate while the robot is in motion. Refer to the Control a ROS-Enabled Robot with a Function section, which shows how to publish a new set of destination coordinates through a virtual machine terminal.

Terminate the generated ROS node by using the stopNode function of the rosDevice object. Alternatively, you can terminate the execution by pressing Ctrl-C or sending a message to the /stop topic. Reset the Gazebo scene.

stopNode(gazeboVMDevice,'robotROSFeedbackControlCodegen')
call(gazeboResetClient);

Shut down the ROS system.

rosshutdown
Shutting down global node /matlab_global_node_12273 with NodeURI http://192.168.192.1:57204/ and MasterURI http://192.168.192.132:11311.

Related Topics