48 marker.type = Marker::CUBE;
49 marker.scale.x = msg.scale * 0.45;
50 marker.scale.y = msg.scale * 0.45;
51 marker.scale.z = msg.scale * 0.45;
62 InteractiveMarkerControl control;
63 control.always_visible =
true;
64 control.markers.push_back(
makeBox(msg) );
65 msg.controls.push_back( control );
67 return msg.controls.back();
73 InteractiveMarker int_marker;
74 int_marker.header.frame_id =
"/base_link";
78 int_marker.name =
"simple_6dof";
79 int_marker.description =
"Simple 6-DOF Control";
84 InteractiveMarkerControl control;
88 int_marker.name +=
"_fixed";
89 int_marker.description +=
"\n(fixed orientation)";
90 control.orientation_mode = InteractiveMarkerControl::FIXED;
93 control.orientation.w = 1;
94 control.orientation.x = 1;
95 control.orientation.y = 0;
96 control.orientation.z = 0;
97 control.name =
"rotate_x";
98 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
99 int_marker.controls.push_back(control);
100 control.name =
"move_x";
101 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
102 int_marker.controls.push_back(control);
104 control.orientation.w = 1;
105 control.orientation.x = 0;
106 control.orientation.y = 1;
107 control.orientation.z = 0;
108 control.name =
"rotate_z";
109 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
110 int_marker.controls.push_back(control);
111 control.name =
"move_z";
112 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
113 int_marker.controls.push_back(control);
115 control.orientation.w = 1;
116 control.orientation.x = 0;
117 control.orientation.y = 0;
118 control.orientation.z = 1;
119 control.name =
"rotate_y";
120 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
121 int_marker.controls.push_back(control);
122 control.name =
"move_y";
123 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
124 int_marker.controls.push_back(control);
126 server->insert(int_marker);
132 static bool sending =
true;
134 geometry_msgs::Pose pose;
135 pose.orientation.w = 1;
140 header.frame_id =
"/base_link";
143 int seconds = time.
toSec();
147 if ( seconds % 4 < 2 )
156 header.frame_id =
"missing_frame";
159 server->setPose(
"simple_6dof",pose,header);
160 server->applyChanges();
168 int main(
int argc,
char** argv)
179 server->applyChanges();
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
Marker makeBox(InteractiveMarker &msg)
void make6DofMarker(bool fixed)
InteractiveMarkerControl & makeBoxControl(InteractiveMarker &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
void frameCallback(const ros::TimerEvent &)