#include <footstep_marker.h>
Public Types | |
| enum | CommandMode { SINGLE, CONTINUOUS, STACK } |
| typedef FootstepMarkerConfig | Config |
| typedef jsk_footstep_msgs::ExecFootstepsResult | ExecResult |
| typedef actionlib::SimpleActionClient < jsk_footstep_msgs::ExecFootstepsAction > | ExecuteActionClient |
| typedef boost::function< void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &)> | MenuCallbackFunction |
| typedef actionlib::SimpleActionClient < jsk_footstep_msgs::PlanFootstepsAction > | PlanningActionClient |
| enum | PlanningState { NOT_STARTED, FINISHED, ON_GOING } |
| typedef jsk_footstep_msgs::PlanFootstepsResult | PlanResult |
| typedef boost::shared_ptr < FootstepMarker > | Ptr |
Public Member Functions | |
| FootstepMarker () | |
| virtual | ~FootstepMarker () |
Protected Member Functions | |
| virtual void | callFollowPathPlan (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | cancelPlanning () |
| virtual void | configCallback (Config &config, uint32_t level) |
| virtual visualization_msgs::Marker | distanceLineMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual visualization_msgs::Marker | distanceTextMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual void | enable2DCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enable3DCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enableContinuousCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enableCubeCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enableLineCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enableSingleCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | enableStackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | executeDoneCB (const actionlib::SimpleClientGoalState &state, const ExecResult::ConstPtr &result) |
| virtual void | executeFootstepCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual bool | executeFootstepService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| virtual jsk_footstep_msgs::FootstepArray | footstepArrayFromPosePair (PosePair::Ptr pose_pair, const std_msgs::Header &header, bool is_lleg_first) |
| virtual PosePair::Ptr | getCurrentFootstepPoses (const ros::Time &stamp) |
| virtual PosePair::Ptr | getDefaultFootstepPair () |
| virtual FootstepTrans | getDefaultLeftLegOffset () |
| virtual FootstepTrans | getDefaultRightLegOffset () |
| virtual bool | getFootstepMarkerPoseService (jsk_interactive_marker::GetTransformableMarkerPose::Request &req, jsk_interactive_marker::GetTransformableMarkerPose::Response &res) |
| virtual PosePair::Ptr | getLatestCurrentFootstepPoses () |
| virtual visualization_msgs::Marker | goalBoundingBoxMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual visualization_msgs::Marker | makeFootstepMarker (FootstepTrans pose, unsigned char leg) |
| virtual visualization_msgs::Marker | originBoundingBoxMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual visualization_msgs::Marker | originMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual void | plan (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | planDoneCB (const actionlib::SimpleClientGoalState &state, const PlanResult::ConstPtr &result) |
| virtual void | planIfPossible (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | poseStampedCommandCallback (const geometry_msgs::PoseStamped::ConstPtr &msg) |
| virtual void | processFeedbackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | processMenuFeedbackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | processPoseUpdateCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual void | publishCurrentMarkerMode () |
| virtual void | resetInteractiveMarker () |
| virtual void | resetMarkerCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual bool | resetMarkerService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| virtual void | setupGoalMarker (FootstepTrans pose, visualization_msgs::InteractiveMarker &int_marker) |
| virtual void | setupInitialMarker (PosePair::Ptr leg_poses, visualization_msgs::InteractiveMarker &int_marker) |
| virtual void | setupMenuHandler () |
| virtual visualization_msgs::Marker | stackedPosesMarker (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual void | stackFootstepCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| virtual bool | stackMarkerPoseService (jsk_interactive_marker::SetPose::Request &req, jsk_interactive_marker::SetPose::Response &res) |
| virtual visualization_msgs::Marker | targetArrow (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual bool | toggleFootstepMarkerModeService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| virtual void | updateMarkerArray (const std_msgs::Header &header, const geometry_msgs::Pose &pose) |
| virtual bool | waitForExecuteFootstepService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| virtual bool | waitForFootstepPlanService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
Protected Attributes | |
| ExecuteActionClient | ac_exec_ |
| PlanningActionClient | ac_planner_ |
| FootstepTrans | collision_bbox_offset_ |
| FootstepVec | collision_bbox_size_ |
| CommandMode | command_mode_ |
| interactive_markers::MenuHandler::EntryHandle | cont_mode_ |
| interactive_markers::MenuHandler::EntryHandle | cube_mode_ |
| FootstepTrans | current_lleg_offset_ |
| FootstepTrans | current_rleg_offset_ |
| double | default_footstep_margin_ |
| bool | disable_tf_ |
| interactive_markers::MenuHandler::EntryHandle | entry_2d_mode_ |
| interactive_markers::MenuHandler::EntryHandle | entry_3d_mode_ |
| double | foot_size_x_ |
| double | foot_size_y_ |
| double | foot_size_z_ |
| bool | have_last_step_ |
| bool | is_2d_mode_ |
| bool | is_cube_mode_ |
| jsk_footstep_msgs::Footstep | last_steps_ [2] |
| interactive_markers::MenuHandler::EntryHandle | line_mode_ |
| std::string | lleg_end_coords_ |
| FootstepVec | lleg_footstep_offset_ |
| FootstepTrans | lleg_goal_pose_ |
| interactive_markers::MenuHandler | menu_handler_ |
| ros::NodeHandle | nh_ |
| std::string | odom_frame_id_ |
| PosePair::Ptr | original_foot_poses_ |
| jsk_footstep_msgs::FootstepArray | plan_result_ |
| boost::mutex | planner_mutex_ |
| PlanningState | planning_state_ |
| ros::NodeHandle | pnh_ |
| ros::Publisher | pub_current_marker_mode_ |
| MarkerArrayPublisher | pub_marker_array_ |
| ros::Publisher | pub_plan_result_ |
| std::string | rleg_end_coords_ |
| FootstepVec | rleg_footstep_offset_ |
| FootstepTrans | rleg_goal_pose_ |
| boost::shared_ptr < interactive_markers::InteractiveMarkerServer > | server_ |
| interactive_markers::MenuHandler::EntryHandle | single_mode_ |
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
| ros::ServiceServer | srv_execute_footstep_ |
| ros::ServiceServer | srv_get_fs_marker_pose_ |
| ros::ServiceServer | srv_reset_fs_marker_ |
| ros::ServiceServer | srv_stack_marker_pose_ |
| ros::ServiceServer | srv_toggle_fs_com_mode_ |
| ros::ServiceServer | srv_wait_for_exec_fs_ |
| ros::ServiceServer | srv_wait_for_fs_plan_ |
| interactive_markers::MenuHandler::EntryHandle | stack_btn_ |
| interactive_markers::MenuHandler::EntryHandle | stack_mode_ |
| std::vector< FootstepTrans > | stacked_poses_ |
| ros::Subscriber | sub_pose_stamped_command_ |
| boost::shared_ptr < tf2_ros::BufferClient > | tf_client_ |
| bool | use_default_goal_ |
Definition at line 96 of file footstep_marker.h.
| typedef FootstepMarkerConfig jsk_footstep_planner::FootstepMarker::Config |
Definition at line 111 of file footstep_marker.h.
| typedef jsk_footstep_msgs::ExecFootstepsResult jsk_footstep_planner::FootstepMarker::ExecResult |
Definition at line 105 of file footstep_marker.h.
| typedef actionlib::SimpleActionClient<jsk_footstep_msgs::ExecFootstepsAction> jsk_footstep_planner::FootstepMarker::ExecuteActionClient |
Definition at line 103 of file footstep_marker.h.
| typedef boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> jsk_footstep_planner::FootstepMarker::MenuCallbackFunction |
Definition at line 107 of file footstep_marker.h.
| typedef actionlib::SimpleActionClient<jsk_footstep_msgs::PlanFootstepsAction> jsk_footstep_planner::FootstepMarker::PlanningActionClient |
Definition at line 101 of file footstep_marker.h.
| typedef jsk_footstep_msgs::PlanFootstepsResult jsk_footstep_planner::FootstepMarker::PlanResult |
Definition at line 104 of file footstep_marker.h.
| typedef boost::shared_ptr<FootstepMarker> jsk_footstep_planner::FootstepMarker::Ptr |
Definition at line 99 of file footstep_marker.h.
Definition at line 110 of file footstep_marker.h.
Definition at line 109 of file footstep_marker.h.
Definition at line 136 of file footstep_marker.cpp.
| FootstepMarker::~FootstepMarker | ( | ) | [virtual] |
Definition at line 214 of file footstep_marker.cpp.
| void FootstepMarker::callFollowPathPlan | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 1277 of file footstep_marker.cpp.
| void FootstepMarker::cancelPlanning | ( | ) | [protected, virtual] |
Definition at line 660 of file footstep_marker.cpp.
| void FootstepMarker::configCallback | ( | Config & | config, |
| uint32_t | level | ||
| ) | [protected, virtual] |
Definition at line 1074 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::distanceLineMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 814 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::distanceTextMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 896 of file footstep_marker.cpp.
| void FootstepMarker::enable2DCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 536 of file footstep_marker.cpp.
| void FootstepMarker::enable3DCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 551 of file footstep_marker.cpp.
| void FootstepMarker::enableContinuousCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 595 of file footstep_marker.cpp.
| void FootstepMarker::enableCubeCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 508 of file footstep_marker.cpp.
| void FootstepMarker::enableLineCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 522 of file footstep_marker.cpp.
| void FootstepMarker::enableSingleCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 566 of file footstep_marker.cpp.
| void FootstepMarker::enableStackCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 624 of file footstep_marker.cpp.
| void FootstepMarker::executeDoneCB | ( | const actionlib::SimpleClientGoalState & | state, |
| const ExecResult::ConstPtr & | result | ||
| ) | [protected, virtual] |
Definition at line 431 of file footstep_marker.cpp.
| void FootstepMarker::executeFootstepCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 449 of file footstep_marker.cpp.
| bool FootstepMarker::executeFootstepService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1166 of file footstep_marker.cpp.
| jsk_footstep_msgs::FootstepArray FootstepMarker::footstepArrayFromPosePair | ( | PosePair::Ptr | pose_pair, |
| const std_msgs::Header & | header, | ||
| bool | is_lleg_first | ||
| ) | [protected, virtual] |
Definition at line 669 of file footstep_marker.cpp.
| PosePair::Ptr FootstepMarker::getCurrentFootstepPoses | ( | const ros::Time & | stamp | ) | [protected, virtual] |
Definition at line 1054 of file footstep_marker.cpp.
| PosePair::Ptr FootstepMarker::getDefaultFootstepPair | ( | ) | [protected, virtual] |
Definition at line 1031 of file footstep_marker.cpp.
| FootstepTrans FootstepMarker::getDefaultLeftLegOffset | ( | ) | [protected, virtual] |
Definition at line 753 of file footstep_marker.cpp.
| FootstepTrans FootstepMarker::getDefaultRightLegOffset | ( | ) | [protected, virtual] |
Definition at line 757 of file footstep_marker.cpp.
| bool FootstepMarker::getFootstepMarkerPoseService | ( | jsk_interactive_marker::GetTransformableMarkerPose::Request & | req, |
| jsk_interactive_marker::GetTransformableMarkerPose::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1208 of file footstep_marker.cpp.
| PosePair::Ptr FootstepMarker::getLatestCurrentFootstepPoses | ( | ) | [protected, virtual] |
Definition at line 1039 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::goalBoundingBoxMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 942 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::makeFootstepMarker | ( | FootstepTrans | pose, |
| unsigned char | leg | ||
| ) | [protected, virtual] |
Definition at line 221 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::originBoundingBoxMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 926 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::originMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 868 of file footstep_marker.cpp.
| void FootstepMarker::plan | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 696 of file footstep_marker.cpp.
| void FootstepMarker::planDoneCB | ( | const actionlib::SimpleClientGoalState & | state, |
| const PlanResult::ConstPtr & | result | ||
| ) | [protected, virtual] |
Definition at line 735 of file footstep_marker.cpp.
| void FootstepMarker::planIfPossible | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 744 of file footstep_marker.cpp.
| void FootstepMarker::poseStampedCommandCallback | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) | [protected, virtual] |
Definition at line 1083 of file footstep_marker.cpp.
| void FootstepMarker::processFeedbackCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 761 of file footstep_marker.cpp.
| void FootstepMarker::processMenuFeedbackCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 655 of file footstep_marker.cpp.
| void FootstepMarker::processPoseUpdateCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 1026 of file footstep_marker.cpp.
| void FootstepMarker::publishCurrentMarkerMode | ( | ) | [protected, virtual] |
Definition at line 1244 of file footstep_marker.cpp.
| void FootstepMarker::resetInteractiveMarker | ( | ) | [protected, virtual] |
Definition at line 316 of file footstep_marker.cpp.
| void FootstepMarker::resetMarkerCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 421 of file footstep_marker.cpp.
| bool FootstepMarker::resetMarkerService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1124 of file footstep_marker.cpp.
| void FootstepMarker::setupGoalMarker | ( | FootstepTrans | pose, |
| visualization_msgs::InteractiveMarker & | int_marker | ||
| ) | [protected, virtual] |
Definition at line 292 of file footstep_marker.cpp.
| void FootstepMarker::setupInitialMarker | ( | PosePair::Ptr | leg_poses, |
| visualization_msgs::InteractiveMarker & | int_marker | ||
| ) | [protected, virtual] |
Definition at line 267 of file footstep_marker.cpp.
| void FootstepMarker::setupMenuHandler | ( | ) | [protected, virtual] |
Definition at line 364 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::stackedPosesMarker | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 960 of file footstep_marker.cpp.
| void FootstepMarker::stackFootstepCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [protected, virtual] |
Definition at line 438 of file footstep_marker.cpp.
| bool FootstepMarker::stackMarkerPoseService | ( | jsk_interactive_marker::SetPose::Request & | req, |
| jsk_interactive_marker::SetPose::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1227 of file footstep_marker.cpp.
| visualization_msgs::Marker FootstepMarker::targetArrow | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 799 of file footstep_marker.cpp.
| bool FootstepMarker::toggleFootstepMarkerModeService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1136 of file footstep_marker.cpp.
| void FootstepMarker::updateMarkerArray | ( | const std_msgs::Header & | header, |
| const geometry_msgs::Pose & | pose | ||
| ) | [protected, virtual] |
Definition at line 1014 of file footstep_marker.cpp.
| bool FootstepMarker::waitForExecuteFootstepService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1184 of file footstep_marker.cpp.
| bool FootstepMarker::waitForFootstepPlanService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 1196 of file footstep_marker.cpp.
Definition at line 217 of file footstep_marker.h.
Definition at line 216 of file footstep_marker.h.
Definition at line 261 of file footstep_marker.h.
Definition at line 260 of file footstep_marker.h.
Definition at line 252 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::cont_mode_ [protected] |
Definition at line 248 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::cube_mode_ [protected] |
Definition at line 245 of file footstep_marker.h.
Definition at line 233 of file footstep_marker.h.
Definition at line 233 of file footstep_marker.h.
double jsk_footstep_planner::FootstepMarker::default_footstep_margin_ [protected] |
Definition at line 235 of file footstep_marker.h.
bool jsk_footstep_planner::FootstepMarker::disable_tf_ [protected] |
Definition at line 255 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::entry_2d_mode_ [protected] |
Definition at line 243 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::entry_3d_mode_ [protected] |
Definition at line 244 of file footstep_marker.h.
double jsk_footstep_planner::FootstepMarker::foot_size_x_ [protected] |
Definition at line 254 of file footstep_marker.h.
double jsk_footstep_planner::FootstepMarker::foot_size_y_ [protected] |
Definition at line 254 of file footstep_marker.h.
double jsk_footstep_planner::FootstepMarker::foot_size_z_ [protected] |
Definition at line 254 of file footstep_marker.h.
bool jsk_footstep_planner::FootstepMarker::have_last_step_ [protected] |
Definition at line 263 of file footstep_marker.h.
bool jsk_footstep_planner::FootstepMarker::is_2d_mode_ [protected] |
Definition at line 250 of file footstep_marker.h.
bool jsk_footstep_planner::FootstepMarker::is_cube_mode_ [protected] |
Definition at line 251 of file footstep_marker.h.
jsk_footstep_msgs::Footstep jsk_footstep_planner::FootstepMarker::last_steps_[2] [protected] |
Definition at line 264 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::line_mode_ [protected] |
Definition at line 246 of file footstep_marker.h.
Definition at line 230 of file footstep_marker.h.
Definition at line 234 of file footstep_marker.h.
Definition at line 232 of file footstep_marker.h.
Definition at line 241 of file footstep_marker.h.
Definition at line 212 of file footstep_marker.h.
Definition at line 229 of file footstep_marker.h.
Definition at line 231 of file footstep_marker.h.
jsk_footstep_msgs::FootstepArray jsk_footstep_planner::FootstepMarker::plan_result_ [protected] |
Definition at line 237 of file footstep_marker.h.
Definition at line 258 of file footstep_marker.h.
Definition at line 259 of file footstep_marker.h.
Definition at line 213 of file footstep_marker.h.
Definition at line 219 of file footstep_marker.h.
Definition at line 215 of file footstep_marker.h.
Definition at line 218 of file footstep_marker.h.
Definition at line 230 of file footstep_marker.h.
Definition at line 234 of file footstep_marker.h.
Definition at line 232 of file footstep_marker.h.
boost::shared_ptr<interactive_markers::InteractiveMarkerServer> jsk_footstep_planner::FootstepMarker::server_ [protected] |
Definition at line 239 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::single_mode_ [protected] |
Definition at line 247 of file footstep_marker.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_footstep_planner::FootstepMarker::srv_ [protected] |
Definition at line 240 of file footstep_marker.h.
Definition at line 223 of file footstep_marker.h.
Definition at line 226 of file footstep_marker.h.
Definition at line 221 of file footstep_marker.h.
Definition at line 227 of file footstep_marker.h.
Definition at line 222 of file footstep_marker.h.
Definition at line 224 of file footstep_marker.h.
Definition at line 225 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::stack_btn_ [protected] |
Definition at line 242 of file footstep_marker.h.
interactive_markers::MenuHandler::EntryHandle jsk_footstep_planner::FootstepMarker::stack_mode_ [protected] |
Definition at line 249 of file footstep_marker.h.
Definition at line 265 of file footstep_marker.h.
Definition at line 220 of file footstep_marker.h.
boost::shared_ptr<tf2_ros::BufferClient> jsk_footstep_planner::FootstepMarker::tf_client_ [protected] |
Definition at line 238 of file footstep_marker.h.
bool jsk_footstep_planner::FootstepMarker::use_default_goal_ [protected] |
Definition at line 256 of file footstep_marker.h.