#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) |
Definition at line 128 of file footstep_marker.h.
typedef FootstepMarkerConfig jsk_footstep_planner::FootstepMarker::Config |
Definition at line 143 of file footstep_marker.h.
typedef jsk_footstep_msgs::ExecFootstepsResult jsk_footstep_planner::FootstepMarker::ExecResult |
Definition at line 137 of file footstep_marker.h.
typedef actionlib::SimpleActionClient<jsk_footstep_msgs::ExecFootstepsAction> jsk_footstep_planner::FootstepMarker::ExecuteActionClient |
Definition at line 135 of file footstep_marker.h.
typedef boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> jsk_footstep_planner::FootstepMarker::MenuCallbackFunction |
Definition at line 139 of file footstep_marker.h.
typedef actionlib::SimpleActionClient<jsk_footstep_msgs::PlanFootstepsAction> jsk_footstep_planner::FootstepMarker::PlanningActionClient |
Definition at line 133 of file footstep_marker.h.
typedef jsk_footstep_msgs::PlanFootstepsResult jsk_footstep_planner::FootstepMarker::PlanResult |
Definition at line 136 of file footstep_marker.h.
Definition at line 131 of file footstep_marker.h.
Enumerator | |
---|---|
SINGLE | |
CONTINUOUS | |
STACK |
Definition at line 142 of file footstep_marker.h.
Enumerator | |
---|---|
NOT_STARTED | |
FINISHED | |
ON_GOING |
Definition at line 141 of file footstep_marker.h.
FootstepMarker::FootstepMarker | ( | ) |
Definition at line 136 of file footstep_marker.cpp.
|
virtual |
Definition at line 214 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1277 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 660 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1074 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 814 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 896 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 536 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 551 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 595 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 508 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 522 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 566 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 624 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 431 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 449 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1166 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 669 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1054 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1031 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 753 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 757 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1208 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1039 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 942 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 221 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 926 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 868 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 696 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 735 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 744 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1083 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 761 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 655 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1026 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1244 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 316 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 421 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1124 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 292 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 267 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 364 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 960 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 438 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1227 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 799 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1136 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1014 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1184 of file footstep_marker.cpp.
|
protectedvirtual |
Definition at line 1196 of file footstep_marker.cpp.
|
protected |
Definition at line 249 of file footstep_marker.h.
|
protected |
Definition at line 248 of file footstep_marker.h.
|
protected |
Definition at line 293 of file footstep_marker.h.
|
protected |
Definition at line 292 of file footstep_marker.h.
|
protected |
Definition at line 284 of file footstep_marker.h.
|
protected |
Definition at line 280 of file footstep_marker.h.
|
protected |
Definition at line 277 of file footstep_marker.h.
|
protected |
Definition at line 265 of file footstep_marker.h.
|
protected |
Definition at line 265 of file footstep_marker.h.
|
protected |
Definition at line 267 of file footstep_marker.h.
|
protected |
Definition at line 287 of file footstep_marker.h.
|
protected |
Definition at line 275 of file footstep_marker.h.
|
protected |
Definition at line 276 of file footstep_marker.h.
|
protected |
Definition at line 286 of file footstep_marker.h.
|
protected |
Definition at line 286 of file footstep_marker.h.
|
protected |
Definition at line 286 of file footstep_marker.h.
|
protected |
Definition at line 295 of file footstep_marker.h.
|
protected |
Definition at line 282 of file footstep_marker.h.
|
protected |
Definition at line 283 of file footstep_marker.h.
|
protected |
Definition at line 296 of file footstep_marker.h.
|
protected |
Definition at line 278 of file footstep_marker.h.
|
protected |
Definition at line 262 of file footstep_marker.h.
|
protected |
Definition at line 266 of file footstep_marker.h.
|
protected |
Definition at line 264 of file footstep_marker.h.
|
protected |
Definition at line 273 of file footstep_marker.h.
|
protected |
Definition at line 244 of file footstep_marker.h.
|
protected |
Definition at line 261 of file footstep_marker.h.
|
protected |
Definition at line 263 of file footstep_marker.h.
|
protected |
Definition at line 269 of file footstep_marker.h.
|
protected |
Definition at line 290 of file footstep_marker.h.
|
protected |
Definition at line 291 of file footstep_marker.h.
|
protected |
Definition at line 245 of file footstep_marker.h.
|
protected |
Definition at line 251 of file footstep_marker.h.
|
protected |
Definition at line 247 of file footstep_marker.h.
|
protected |
Definition at line 250 of file footstep_marker.h.
|
protected |
Definition at line 262 of file footstep_marker.h.
|
protected |
Definition at line 266 of file footstep_marker.h.
|
protected |
Definition at line 264 of file footstep_marker.h.
|
protected |
Definition at line 271 of file footstep_marker.h.
|
protected |
Definition at line 279 of file footstep_marker.h.
|
protected |
Definition at line 272 of file footstep_marker.h.
|
protected |
Definition at line 255 of file footstep_marker.h.
|
protected |
Definition at line 258 of file footstep_marker.h.
|
protected |
Definition at line 253 of file footstep_marker.h.
|
protected |
Definition at line 259 of file footstep_marker.h.
|
protected |
Definition at line 254 of file footstep_marker.h.
|
protected |
Definition at line 256 of file footstep_marker.h.
|
protected |
Definition at line 257 of file footstep_marker.h.
|
protected |
Definition at line 274 of file footstep_marker.h.
|
protected |
Definition at line 281 of file footstep_marker.h.
|
protected |
Definition at line 297 of file footstep_marker.h.
|
protected |
Definition at line 252 of file footstep_marker.h.
|
protected |
Definition at line 270 of file footstep_marker.h.
|
protected |
Definition at line 288 of file footstep_marker.h.