10 visualization_msgs::Marker
marker;
11 marker.type = visualization_msgs::Marker::CUBE;
18 marker.pose.orientation.w = 1.0;
29 visualization_msgs::Marker
marker;
30 marker.type = visualization_msgs::Marker::CUBE;
37 marker.pose.orientation.w = 1.0;
49 visualization_msgs::Marker
marker;
50 marker.type = visualization_msgs::Marker::CUBE;
57 marker.pose.orientation.w = 1.0;
68 visualization_msgs::Marker
marker;
69 marker.type = visualization_msgs::Marker::CUBE;
74 marker.pose.position.x = -0.05;
75 marker.pose.position.y = 0.914 - 0.1 -
marker.scale.y/2 ;
76 marker.pose.position.z = 0.9398;
77 marker.pose.orientation.w = 1.0;
89 visualization_msgs::Marker
marker;
90 marker.type = visualization_msgs::Marker::CUBE;
95 marker.pose.position.x = -0.07;
97 marker.pose.position.z = 0.9398;
98 marker.pose.orientation.w = 1.0;
100 switch(position % 5){
134 geometry_msgs::Pose
pose;
137 pose.position.x = -0.523;
138 pose.position.y = 0.270;
140 pose.orientation.w = 0.766;
141 pose.orientation.x = 0;
142 pose.orientation.y = 0;
143 pose.orientation.z = 0.642788;
145 pose.position.x = -0.8;
146 pose.position.y = 0.0;
147 pose.position.z = -0.910;
148 pose.orientation.w = 1.0;
151 return makeFootMarker(
pose,
true);
154 geometry_msgs::Pose
pose;
156 pose.position.x = -0.747;
157 pose.position.y = 0.310;
159 pose.orientation.w = 0.766;
160 pose.orientation.x = 0;
161 pose.orientation.y = 0;
162 pose.orientation.z = 0.642788;
164 pose.position.x = -0.8;
165 pose.position.y = -0.3;
166 pose.position.z = -0.910;
167 pose.orientation.w = 1.0;
169 return makeFootMarker(
pose,
false);
175 visualization_msgs::Marker
marker;
176 marker.type = visualization_msgs::Marker::CUBE;
177 double PADDING_PARAM = 0.01;
178 marker.scale.x = 0.27 + PADDING_PARAM;
179 marker.scale.y = 0.14 + PADDING_PARAM;
200 visualization_msgs::InteractiveMarker mk;
201 mk.header.frame_id =
"/map";
203 mk.name = marker_name;
207 visualization_msgs::InteractiveMarkerControl triangleMarker;
208 triangleMarker.always_visible =
true;
209 triangleMarker.markers.push_back( makeRWallMarker());
210 triangleMarker.markers.push_back( makeLWallMarker());
211 triangleMarker.markers.push_back( makeDoorMarker());
214 for(
int i=0;i<12;i++){
215 triangleMarker.markers.push_back( makeKnobMarker(i));
218 triangleMarker.markers.push_back( makeKnobMarker());
221 if (footstep_show_initial_p_) {
222 for(
size_t i=0; i<2; i++){
223 if(foot_list[i].
header.frame_id ==
"right"){
224 triangleMarker.markers.push_back( makeFootMarker( foot_list[i].
pose,
true ));
226 triangleMarker.markers.push_back( makeFootMarker( foot_list[i].
pose,
false ));
231 int first_index = footstep_index_ * 2;
232 int second_index = footstep_index_ * 2 + 1;
233 if (foot_list.size() > first_index) {
234 triangleMarker.markers.push_back( makeFootMarker( foot_list[first_index].
pose,
235 foot_list[first_index].
header.frame_id ==
"right"));
237 if (foot_list.size() > second_index) {
238 triangleMarker.markers.push_back( makeFootMarker( foot_list[second_index].
pose,
239 foot_list[second_index].
header.frame_id ==
"right"));
245 mk.controls.push_back( triangleMarker );
253 door_pose = feedback->pose;
258 footstep_show_initial_p_ =
true;
259 updateBoxInteractiveMarker();
262 if (foot_list.size() > 2) {
263 if (footstep_show_initial_p_) {
265 footstep_show_initial_p_ =
false;
269 if (foot_list.size() / 2 == footstep_index_) {
274 updateBoxInteractiveMarker();
277 if (foot_list.size() > 2) {
278 if (footstep_show_initial_p_) {
280 footstep_show_initial_p_ =
false;
284 if (footstep_index_ == 0) {
285 footstep_index_ = (foot_list.size() - 1)/ 2;
289 updateBoxInteractiveMarker();
294 updateBoxInteractiveMarker();
299 updateBoxInteractiveMarker();
315 visualization_msgs::InteractiveMarker boxIM = makeInteractiveMarker();
317 server_->insert(boxIM,
319 menu_handler.apply(*server_, marker_name);
320 server_->applyChanges();
334 for(
int i=0; i<
v.size(); i++){
336 geometry_msgs::Pose
p =
getPose(foot[
"pose"]);
337 geometry_msgs::PoseStamped footPose;
339 footPose.header.frame_id.assign(foot[
"leg"]);
354 int main(
int argc,
char** argv)
365 geometry_msgs::Pose
p;
383 return (
double)((int)val);