windows系统下安装和使用ROS的解决方案 (1 win_ros 2 rosserial_windows)
具体请参考官网:
2 https://github.com/ros-windows/win_ros
3 http://wiki.ros.org/rosserial_windows
4 http://wiki.ros.org/rosserial_windows/Tutorials
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:
- From the ROS based system, generate the ros_lib code
- Drop the ros_lib code into a Visual Studios Solution
- Write code to use ros_lib to connect to the ROS master and send/receive messages
- Run rosserial_server socket on ROS master
- 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
- Open Visual Studio
-
File -> New Project
-
Find the Win32 Console Application under Installed -> Templates -> Visual C++ -> Win32
- Give your project a name. We'll use rosserial_hello_world
- 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:
- ros.h
- duration.cpp
- time.cpp
-
WindowsSocket.cpp
Then add the ros_lib folder to your includes path by:
- Right-click on the rosserial_hello_world project in the Solution Explorer and go to Properties
- 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!
----
Receiving Messages in rosserial_windows
Description: An example of receiving messages in rosserial_windows
Keywords: rosserial, windows, rosserial_windows
Tutorial Level: INTERMEDIATE
目录
Introduction
By now you've learned how to say Hello World with rosserial_windows. But what about if you want to receive a message? This tutorial will guide you through receiving messages in rosserial_windows
Using a Callback Function
Receiving a message is a little more complicated than sending, but only slightly. You'll need to tell the node handle what to do when you receive a message. Specifically, we'll use a callback function that gets called when a message is received.
Let's say that you want to receive the estimated pose of the robot. Whenever that happens, you'll want to print out the pose. Here's a function that might do that.
That is an example of a callback function. It handles a new pose, in this case by printing to the screen. The next question is how do you get this called when receiving a new message? Assuming that you've already connected to the ROS master and have a NodeHandle called nh, here's how you would do that:
Receiving Messages
Now you have a callback and you've subscribed, but if you don't actually give rosserial a chance to process messages you won't receive anything. Fortunately, we've been doing that all along. That's what this bit of code does:
All this does is give rosserial a chance to process messages and then sleep for a bit. The sleep is optional, though I don't recommend just calling spinOnce(). If you have other elements that you need to call that block for short periods, put them in this loop. Otherwise, beware that going too long between calling spinOnce() will produce disconnects.
Example
Here's the full example of how to receive messages.
1 #include "stdafx.h"
2 #include <string>
3 #include <stdio.h>
4 #include "ros.h"
5 #include <geometry_msgs/PoseWithCovarianceStamped.h>
6 #include <windows.h>
7
8 using std::string;
9
10 void estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose)
11 {
12 printf ("Received pose %f, %f, %f\n", pose.pose.pose.position.x,
13 pose.pose.pose.position.y, pose.pose.pose.position.z);
14 }
15
16 int _tmain (int argc, _TCHAR * argv[])
17 {
18 ros::NodeHandle nh;
19 char *ros_master = "1.2.3.4";
20
21 printf ("Connecting to server at %s\n", ros_master);
22 nh.initNode (ros_master);
23
24 ros::Subscriber < geometry_msgs::PoseWithCovarianceStamped >
25 poseSub ("estimated_pose", &estimated_pose_callback);
26 nh.subscribe (poseSub);
27
28 printf ("Waiting to receive messages\n");
29 while (1)
30 {
31 nh.spinOnce ();
32 Sleep (100);
33 }
34
35 printf ("All done!\n");
36 return 0;
37 }
Running it all together
Again, assuming the Husky/Gazebo simulation from ROS 101 Drive a Husky, here's how to receive the pose from odometry:
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 estimated_pose topic remapped to the odometry result from robot EKF:
rosrun rosserial_server socket_node estimated_pose:=/robot_pose_ekf/odom
Now run the app, and you should be receiving pose messages. If not, check that the mapping is correct, using rostopic if necessary.
Class-based Approach
It's possible to subclass the Subscriber class for a more object-oriented approach. In that case, instead of registering with the call back above simply instantiate the new class and pass that in to the subscribe call.