#include <door_foot.h>
| Public Member Functions | |
| DoorFoot () | |
| visualization_msgs::Marker | makeDoorMarker () | 
| visualization_msgs::Marker | makeFootMarker (geometry_msgs::Pose pose, bool right) | 
| visualization_msgs::InteractiveMarker | makeInteractiveMarker () | 
| visualization_msgs::Marker | makeKnobMarker () | 
| visualization_msgs::Marker | makeKnobMarker (int position) | 
| visualization_msgs::Marker | makeLFootMarker () | 
| visualization_msgs::Marker | makeLWallMarker () | 
| interactive_markers::MenuHandler | makeMenuHandler () | 
| visualization_msgs::Marker | makeRFootMarker () | 
| visualization_msgs::Marker | makeRWallMarker () | 
| void | moveBoxCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | procAnimation () | 
| void | pullDoorCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | pushDoorCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | showNextStepCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | showPreviousStepCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | showStandLocationCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | updateBoxInteractiveMarker () | 
| Private Attributes | |
| geometry_msgs::Pose | door_pose | 
| std::vector < geometry_msgs::PoseStamped > | foot_list | 
| int | footstep_index_ | 
| bool | footstep_show_initial_p_ | 
| std::string | marker_name | 
| interactive_markers::MenuHandler | menu_handler | 
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | pnh_ | 
| bool | push | 
| std::shared_ptr < interactive_markers::InteractiveMarkerServer > | server_ | 
| std::string | server_name | 
| double | size_ | 
| bool | use_color_knob | 
Definition at line 9 of file door_foot.h.
Definition at line 323 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeDoorMarker | ( | ) | 
Definition at line 48 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeFootMarker | ( | geometry_msgs::Pose | pose, | 
| bool | right | ||
| ) | 
Definition at line 174 of file door_foot.cpp.
| visualization_msgs::InteractiveMarker DoorFoot::makeInteractiveMarker | ( | ) | 
Definition at line 199 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeKnobMarker | ( | ) | 
Definition at line 67 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeKnobMarker | ( | int | position | ) | 
Definition at line 87 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeLFootMarker | ( | ) | 
Definition at line 153 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeLWallMarker | ( | ) | 
Definition at line 28 of file door_foot.cpp.
Definition at line 303 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeRFootMarker | ( | ) | 
Definition at line 133 of file door_foot.cpp.
| visualization_msgs::Marker DoorFoot::makeRWallMarker | ( | ) | 
Definition at line 9 of file door_foot.cpp.
| void DoorFoot::moveBoxCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 251 of file door_foot.cpp.
| void DoorFoot::procAnimation | ( | ) | 
| void DoorFoot::pullDoorCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 297 of file door_foot.cpp.
| void DoorFoot::pushDoorCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 292 of file door_foot.cpp.
| void DoorFoot::showNextStepCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 261 of file door_foot.cpp.
| void DoorFoot::showPreviousStepCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 276 of file door_foot.cpp.
| void DoorFoot::showStandLocationCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 257 of file door_foot.cpp.
| void DoorFoot::updateBoxInteractiveMarker | ( | ) | 
Definition at line 314 of file door_foot.cpp.
| geometry_msgs::Pose DoorFoot::door_pose  [private] | 
Definition at line 48 of file door_foot.h.
| std::vector<geometry_msgs::PoseStamped> DoorFoot::foot_list  [private] | 
Definition at line 47 of file door_foot.h.
| int DoorFoot::footstep_index_  [private] | 
Definition at line 35 of file door_foot.h.
| bool DoorFoot::footstep_show_initial_p_  [private] | 
Definition at line 34 of file door_foot.h.
| std::string DoorFoot::marker_name  [private] | 
Definition at line 41 of file door_foot.h.
Definition at line 43 of file door_foot.h.
| ros::NodeHandle DoorFoot::nh_  [private] | 
Definition at line 36 of file door_foot.h.
| ros::NodeHandle DoorFoot::pnh_  [private] | 
Definition at line 37 of file door_foot.h.
| bool DoorFoot::push  [private] | 
Definition at line 45 of file door_foot.h.
| std::shared_ptr<interactive_markers::InteractiveMarkerServer> DoorFoot::server_  [private] | 
Definition at line 38 of file door_foot.h.
| std::string DoorFoot::server_name  [private] | 
Definition at line 40 of file door_foot.h.
| double DoorFoot::size_  [private] | 
Definition at line 44 of file door_foot.h.
| bool DoorFoot::use_color_knob  [private] | 
Definition at line 46 of file door_foot.h.