rostopic
toolWe've looked at how we can publish messages, now it's time to do it in C++.
Before we do that though, let's write a node.
#include <iostream>
int main(int argc, char** argv)
{
std::cout << "Hello World!" << std::endl;
}
cd catkin_ws # cd to where your catkin workspace is located
catkin_make
Now, try running the executable with rosrun
igvc_training_exercises
week2_publisher
.How do you run week2_publisher
?
rosrun igvc_training_exercises week2_publisher
Hello World
#include
for the ROS headers at the top of the file.#include <ros/ros.h> // <-- Add this line
#include <iostream>
...
Next, add ros::init(argc, argv, "week2")
above the std::cout
:
int main(int argc, char** argv)
{
ros::init(argc, argv, "week2"); // <-- Add this line
std::cout << "Hello World!" << std::endl;
}
ros::init(argc, argv, "NODE_NAME")
catkin_make
and run the node again to verify that it still worksroscore
running in a separate window, as ROS needs roscore
to work.Hello World
being printed outros::spin()
int main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
std::cout << "Hello World!" << std::endl;
ros::spin(); // <-- Add this line
}
ros::spin()
does. All you need to know is that it stops the program from exiting until
you do Ctrl-C to stop it.rosnode list
week2
node show up:/rosout
/week2
Now, let's write a simple publisher that publishes a number. To do that, we need to do four things:
ros::NodeHandle
ros::NodeHandle
as a "handle" for the ROS noderos::NodeHandle
by adding the following line in the main function:int main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
ros::NodeHandle nh; // <-- Add this line
std::cout << "Hello World!" << std::endl;
ros::spin();
}
ros::Publisher
Now we can create a ros::Publisher
for the node.
ros::NodeHandle
has a function advertise
that creates a ros::Publisher
std_msgs::Int32
.my_number
std_msgs
is a library provided by ROS for creating messages for standard types
Add an include for the std_msgs/Int32.h
:
#include <ros/ros.h>
#include <std_msgs/Int32.h> // <-- Add this line
#include <iostream>
...
Then call the function on the nh
node handle we just created, and store the result in a publisher:
int main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
ros::NodeHandle nh;
// Add the line below
ros::Publisher integer_pub = nh.advertise<std_msgs::Int32>("my_number", 1);
std::cout << "Hello World!" << std::endl;
ros::spin();
}
nh.advertise<TYPE>(TOPIC_NAME, QUEUE_SIZE)
std_msgs::Int32
, as a template argument to the advertise
functionNow that we've got a publisher, let's publish a message.
std_msgs::Int32
, we make a variable of the same typeint main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
ros::NodeHandle nh;
ros::Publisher integer_pub = nh.advertise<std_msgs::Int32>("my_number", 1);
std_msgs::Int32 message; // <-- Add this line
std::cout << "Hello World!" << std::endl;
ros::spin();
}
message.
in the line belowdata
of type int
message.data
to any number you like:int main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
ros::NodeHandle nh;
ros::Publisher integer_pub = nh.advertise<std_msgs::Int32>("my_number", 1);
std_msgs::Int32 message;
message.data = 13; // <-- Add this line
std::cout << "Hello World!" << std::endl;
ros::spin();
}
publish()
function for the ros::Publisher
To actually publish the message, we call integer_pub.publish
and pass the std_msgs::Int32
message we just created
as an argument:
int main(int argc, char** argv)
{
ros::init(argc, argv, "week2");
ros::NodeHandle nh;
ros::Publisher integer_pub = nh.advertise<std_msgs::Int32>("my_number", 1);
std_msgs::Int32 message;
message.data = 13; // <-- Add these lines
integer_pub.publish(message); // <--
std::cout << "Hello World!" << std::endl;
ros::spin();
}
ros::Duration(1).sleep()
to sleep for one second ...
ros::Publisher integer_pub = nh.advertise<std_msgs::Int32>("my_number", 1);
ros::Duration(1).sleep() // <-- Add in a sleep here to give time to subscribers to connect.
std_msgs::Int32 message;
message.data = 13;
integer_pub.publish(message);
...
catkin_make
, then run with rosrun
week2_publisher
) rosrun igvc_training_exercises week2_publisher
A message should be published to the `my_number` topic
How do you see the message that the node published?
rostopic echo /my_number
Make sure you run the command before you launch the week2
node. You should see something like this.
data: 13
Now that we've written a publisher, let's write a subscriber
subscriber
instead#include <ros/ros.h>
ros::NodeHandle
Since we need to do ROS things, ie. create a Subscriber, we need a ros::NodeHandle
also
ros::NodeHandle
?ros::NodeHandle nh;
ros::Subscriber
ros::Subscriber
.ros::Publisher
, we can create a ros::Subscriber
by calling the subscribe
function on
ros::NodeHandle
:ros::Subscriber integer_sub = nh.subscribe("my_number", 1, integerCallback);
nh.subscribe(TOPIC_NAME, QUEUE_SIZE, CALLBACK_FUNCTION);
integerCallback
function)integerCallback
function was something like belowvoid integerCallback(std_msgs::Int32 message)
{
std::cout << "I received a message: " << message.data << std::endl;
}
integerCallback(new_message) // You can imagine that this is happening somewhere.
main
function: void integerCallback(std_msgs::Int32 message)
{
ROS_INFO_STREAM("I received a message: " << message.data);
}
ROS_INFO_STREAM
catkin_make
and testing it outrosrun
, then run the publisher nodeAnd...... nothing gets printed. What's happening?
ros::spin()
The subscriber node doesn't have the ros::spin
ros::spin()
doros::spin
function right after we call nh.subscribe
[ INFO] [1565078804.617569525]: I received a message: 13
If you're not seeing the message print correctly, make sure that you run the subscriber node first, and then the publisher node afterwards, otherwise the publisher node might publish before the subscriber node has a chance to receive the message.
ros::init(argc, argv, "NODE_NAME")
ros::NodeHandle
ros::Publisher publisher = nh.advertise<MESSAGE_TYPE>(TOPIC, QUEUE_SIZE)
publisher.publish(message)
ros::NodeHandle
ros::Subscriber subscriber = nh.subscribe(TOPIC, QUEUE_SIZE, CALLBACK_FUNCTION)
ros::spin()
to let ROS handle the messagesNext week we'll learn about launch files and PID, and get to (properly) play with the simulator.
See you next week!