33 #include <visualization_msgs/Marker.h> 37 int main(
int argc,
char** argv )
47 uint32_t shape = visualization_msgs::Marker::CUBE;
53 visualization_msgs::Marker marker;
55 marker.header.frame_id =
"/my_frame";
62 marker.ns =
"basic_shapes";
73 marker.action = visualization_msgs::Marker::ADD;
78 marker.pose.position.x = 0;
79 marker.pose.position.y = 0;
80 marker.pose.position.z = 0;
81 marker.pose.orientation.x = 0.0;
82 marker.pose.orientation.y = 0.0;
83 marker.pose.orientation.z = 0.0;
84 marker.pose.orientation.w = 1.0;
96 marker.color.r = 0.0f;
97 marker.color.g = 1.0f;
98 marker.color.b = 0.0f;
124 case visualization_msgs::Marker::CUBE:
125 shape = visualization_msgs::Marker::SPHERE;
127 case visualization_msgs::Marker::SPHERE:
128 shape = visualization_msgs::Marker::ARROW;
130 case visualization_msgs::Marker::ARROW:
131 shape = visualization_msgs::Marker::CYLINDER;
133 case visualization_msgs::Marker::CYLINDER:
134 shape = visualization_msgs::Marker::CUBE;
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN_ONCE(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const