This example may be run after building mrs_lib by executing rosrun mrs_lib dynamic_publisher_example
.
#include <std_msgs/Float32.h>
#include <geometry_msgs/Point.h>
int main(int argc, char **argv)
{
const std::string node_name("dynamic_publisher_example");
ros::init(argc, argv, node_name);
ros::NodeHandle nh;
ros::Duration slp(0.5);
std_msgs::Float32 float_msg;
geometry_msgs::Point pt_msg;
ROS_INFO("Publishing topics! Use `rostopic list` and `rostopic echo <topic_name>` to see them.");
while (ros::ok())
{
float_msg.data += 666.0f;
dynpub.
publish(
"float_topic", float_msg);
pt_msg.x = float_msg.data/1;
pt_msg.y = float_msg.data/2;
pt_msg.z = float_msg.data/3;
dynpub.
publish(
"point_topic", pt_msg);
dynpub.
publish(
"point_topic", float_msg);
ros::spinOnce();
slp.sleep();
}
return 0;
}