2 #include <visualization_msgs/Marker.h> 4 int main(
int argc,
char** argv )
12 uint32_t shape = visualization_msgs::Marker::MESH_RESOURCE;
16 visualization_msgs::Marker
marker;
18 marker.header.frame_id =
"/map";
23 marker.ns =
"basic_shapes";
28 marker.mesh_resource =
"package://xbot_s/model/sdzn_full/saidi.DAE";
29 marker.mesh_use_embedded_materials =
true;
32 marker.action = visualization_msgs::Marker::ADD;
35 marker.pose.position.x = -2.16865;
36 marker.pose.position.y = 10.2442;
37 marker.pose.position.z = 0;
38 marker.pose.orientation.x = 0.0;
39 marker.pose.orientation.y = 0.0;
40 marker.pose.orientation.z = -0.503664;
41 marker.pose.orientation.w = 0.8639;
44 marker.scale.x = 4.5/3.2;
45 marker.scale.y = 4.5/3.2;
46 marker.scale.z = 4.5/3.2;
50 marker.color.r = 1.0f;
51 marker.color.g = 1.0f;
52 marker.color.b = 1.0f;
54 marker.color.a = 1.0f;
int main(int argc, char **argv)
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)
visualization_msgs::Marker marker
ros::Publisher marker_pub
#define ROS_WARN_ONCE(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const