32 #include <visualization_msgs/Marker.h> 36 int main(
int argc,
char** argv )
38 ros::init(argc, argv,
"points_and_lines");
48 visualization_msgs::Marker points, line_strip, line_list;
49 points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id =
"/my_frame";
50 points.header.stamp = line_strip.header.stamp = line_list.header.stamp =
ros::Time::now();
51 points.ns = line_strip.ns = line_list.ns =
"points_and_lines";
52 points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
53 points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
63 points.type = visualization_msgs::Marker::POINTS;
64 line_strip.type = visualization_msgs::Marker::LINE_STRIP;
65 line_list.type = visualization_msgs::Marker::LINE_LIST;
74 line_strip.scale.x = 0.1;
75 line_list.scale.x = 0.1;
80 points.color.g = 1.0f;
84 line_strip.color.b = 1.0;
85 line_strip.color.a = 1.0;
88 line_list.color.r = 1.0;
89 line_list.color.a = 1.0;
94 for (uint32_t i = 0; i < 100; ++i)
96 float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
97 float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
99 geometry_msgs::Point p;
100 p.x = (int32_t)i - 50;
104 points.points.push_back(p);
105 line_strip.points.push_back(p);
108 line_list.points.push_back(p);
110 line_list.points.push_back(p);
115 marker_pub.
publish(line_strip);
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)