51 marker.type = Marker::CUBE;
52 marker.scale.x = msg.scale * 0.45;
53 marker.scale.y = msg.scale * 0.45;
54 marker.scale.z = msg.scale * 0.45;
65 InteractiveMarkerControl control;
66 control.always_visible =
true;
67 control.markers.push_back(
makeBox(msg) );
68 msg.controls.push_back( control );
70 return msg.controls.back();
76 InteractiveMarker int_marker;
77 int_marker.header.frame_id =
"/base_link";
81 int_marker.name =
"simple_6dof";
82 int_marker.description =
"Simple 6-DOF Control";
87 InteractiveMarkerControl control;
91 int_marker.name +=
"_fixed";
92 int_marker.description +=
"\n(fixed orientation)";
93 control.orientation_mode = InteractiveMarkerControl::FIXED;
96 control.orientation.w = 1;
97 control.orientation.x = 1;
98 control.orientation.y = 0;
99 control.orientation.z = 0;
100 control.name =
"rotate_x";
101 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
102 int_marker.controls.push_back(control);
103 control.name =
"move_x";
104 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
105 int_marker.controls.push_back(control);
107 control.orientation.w = 1;
108 control.orientation.x = 0;
109 control.orientation.y = 1;
110 control.orientation.z = 0;
111 control.name =
"rotate_z";
112 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
113 int_marker.controls.push_back(control);
114 control.name =
"move_z";
115 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
116 int_marker.controls.push_back(control);
118 control.orientation.w = 1;
119 control.orientation.x = 0;
120 control.orientation.y = 0;
121 control.orientation.z = 1;
122 control.name =
"rotate_y";
123 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
124 int_marker.controls.push_back(control);
125 control.name =
"move_y";
126 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
127 int_marker.controls.push_back(control);
129 server->insert(int_marker);
135 static bool sending =
true;
137 geometry_msgs::Pose pose;
138 pose.orientation.w = 1;
142 std_msgs::Header header;
143 header.frame_id =
"/base_link";
146 int seconds = time.
toSec();
150 if ( seconds % 2 < 1 )
158 std::this_thread::sleep_for(std::chrono::microseconds(10000));
166 server->setPose(
"simple_6dof",pose,header);
167 server->applyChanges();
170 int main(
int argc,
char** argv)
181 server->applyChanges();
void make6DofMarker(bool fixed)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
void frameCallback(const ros::TimerEvent &)
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
InteractiveMarkerControl & makeBoxControl(InteractiveMarker &msg)