(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Hello World from Windows

Description: How to publish information to a ROS master from windows using rosserial_windows.

Keywords: rosserial, windows, rosserial_windows

Tutorial Level: INTERMEDIATE

Introduction

Windows machines can do all kinds of thing that are difficult to do in other environments: interface an MYO, displays for end users, and working with Windows-only software. Working with a ROS master from Windows can be difficult. The rosserial_windows package makes it much easier to send and receive ROS messages from Windows. This package generates all of the coded needed to drop into a Visual Studios Solution. The workflow is generally:

  1. From the ROS based system, generate the ros_lib code
  2. Drop the ros_lib code into a Visual Studios Solution
  3. Write code to use ros_lib to connect to the ROS master and send/receive messages
  4. Run rosserial_server socket on ROS master
  5. Compile and run Windows app

This tutorial will guide you through those steps to be up and running with your own project.

Generating the ros_lib

Installing rosserial_windows

Install rosserial_windows and the rosserial server:

sudo apt-get install ros-hydro-rosserial-windows
sudo apt-get install ros-hydro-rosserial-server

Generate ros_lib

This step will generate the code that will be needed in the Visual Studio project to talk to the ROS master. You will need to supply the name of the folder into which to copy the finished files.

rosrun rosserial_windows make_libraries.py my_library

This will place the ros_lib folder in the folder my_library.

Add ros_lib to Visual Studio Project

NB: This tutorial assumes Visual Studio 2013 Express Desktop.

Create a new Win32 Console Application

  1. Open Visual Studio
  2. File -> New Project

  3. Find the Win32 Console Application under Installed -> Templates -> Visual C++ -> Win32

  4. Give your project a name. We'll use rosserial_hello_world
  5. You will probably want to turn off precompile headers. The project should work with them enabled, but precompiled headers have caused problems in the past.

Copy ros_lib into the project

Copy the ros_lib folder into the rosserial_hello_world project folder. The folder structure should look like:

  • rosserial_hello_world/
    • ipch/
    • ros_lib/
      • ros.h
      • WindowsSocket.cpp

      • ... all of the rosserial generated code, including folders for all of the message packages
    • rosserial_hello_world/
      • ReadMe.txt

      • rosserial_hello_world.cpp
      • rosserial_hello_world.vcxproj
      • rosserial_hello_world.vcxproj.filters
      • stdafx.cpp
      • stdafx.h
      • targetver.h
    • rosserial_hello_world.opensdf
    • rosserial_hello_world.sdf
    • rosserial_hello_world.sln
    • rosserial_hello_world.v12.suo

Add ros_lib to project

Add all of the files in the ros_lib folder that aren't in subfolders to your project. As of writing this, those are:

Then add the ros_lib folder to your includes path by:

  1. Right-click on the rosserial_hello_world project in the Solution Explorer and go to Properties
  2. Under C/C++, add "../ros_lib" to the Additional Include Directories property

Add code to main for Hello World

Since we're commanding a robot, why not send a command instead of just a string? Here we'll send the cmd_vel message to command a robot to go forward and spin around. You'll need to change the IP address to match the address of your ROS master.

   1 // rosserial_hello_world.cpp : Example of sending command velocities from Windows using rosserial
   2 //
   3 #include "stdafx.h"
   4 #include <string>
   5 #include <stdio.h>
   6 #include "ros.h"
   7 #include <geometry_msgs/Twist.h>
   8 #include <windows.h>
   9 
  10 using std::string;
  11 
  12 int _tmain (int argc, _TCHAR * argv[])
  13 {
  14   ros::NodeHandle nh;
  15   char *ros_master = "1.2.3.4";
  16 
  17   printf ("Connecting to server at %s\n", ros_master);
  18   nh.initNode (ros_master);
  19 
  20   printf ("Advertising cmd_vel message\n");
  21   geometry_msgs::Twist twist_msg;
  22   ros::Publisher cmd_vel_pub ("cmd_vel", &twist_msg);
  23   nh.advertise (cmd_vel_pub);
  24 
  25   printf ("Go robot go!\n");
  26   while (1)
  27   {
  28     twist_msg.linear.x = 5.1;
  29     twist_msg.linear.y = 0;
  30     twist_msg.linear.z = 0;
  31     twist_msg.angular.x = 0;
  32     twist_msg.angular.y = 0;
  33     twist_msg.angular.z = -1.8;
  34     cmd_vel_pub.publish (&twist_msg);
  35 
  36     nh.spinOnce ();
  37     Sleep (100);
  38   }
  39 
  40   printf ("All done!\n");
  41   return 0;
  42 }

A few notes on this code:

  • A "node handle" is the equivalent to a ROS node. You'll send everything through that handle
  • Use "init_node" to connect to your ROS master. The format is "hostname:port". The default port is 11411 if none is specified
  • The include files are organized by "package/msg.h" so that they match what you would expect from ROS
  • To publish a message, you first need to make a publisher and then advertise that you're publishing a message
  • finally, you can fill in the message data structure and use the publisher to send it
  • Spin once is used for both receiving messages and for any admin on the port, including keeping your connection alive
  • Beware of a precompile headers. They tend to break building the project.

Start ROS and rosserial_server

In order for rosserial_windows to communicate with the ROS master, a server socket is needed to connect. This tutorial uses a TCP socket, but in theory it is also possible to use a serial port. On the ROS master, start the ROS core:

roscore

In a separate terminal, start the rosserial server

rosrun rosserial_server socket_node

In a third terminal, use rostopic to see what your app sends

rostopic echo /cmd_vel

Run the app

Go back to your windows machine and run the app. You should see command velocities start appearing in the rostopic terminal on your ROS master.

Robot Doughnuts

If you set up a robot simulation in Gazebo, you can then see your robot move based on your commands from Windows. For example, if you follow the ROS 101 Drive a Husky tutorial, you can use this to make the Husky do doughnuts. Here's how to set up that simulation.

In one terminal, launch the husky simulator in an empty world:

roslaunch husky_gazebo husky_empty_world.launch

In another terminal, start the rosserial_server with the command velocity topic remapped to where the Husky expects it.

rosrun rosserial_server socket_node cmd_vel:=/husky/cmd_vel

Now run your app again, and watch the Husky spin around!

Wiki: rosserial_windows/Tutorials/Hello World (last edited 2014-07-11 20:39:47 by KareemShehata)