#include <footstep_marker.h>
Definition at line 64 of file footstep_marker.h.
◆ Config
◆ ExecuteActionClient
◆ PlanningActionClient
◆ PlanResult
◆ FootstepMarker()
FootstepMarker::FootstepMarker |
( |
| ) |
|
◆ ~FootstepMarker()
FootstepMarker::~FootstepMarker |
( |
| ) |
|
|
virtual |
◆ callEstimateOcclusion()
void FootstepMarker::callEstimateOcclusion |
( |
| ) |
|
|
protected |
◆ cancelWalk()
void FootstepMarker::cancelWalk |
( |
| ) |
|
|
protected |
◆ changePlannerHeuristic()
void FootstepMarker::changePlannerHeuristic |
( |
const std::string & |
heuristic | ) |
|
|
protected |
◆ computeLegTransformation()
◆ computePolygon()
geometry_msgs::Polygon FootstepMarker::computePolygon |
( |
uint8_t |
leg | ) |
|
|
protected |
◆ configCallback()
void FootstepMarker::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protected |
◆ executeCB()
void FootstepMarker::executeCB |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
|
protected |
◆ executeFootstep()
void FootstepMarker::executeFootstep |
( |
| ) |
|
|
protected |
◆ forceToReplan()
bool FootstepMarker::forceToReplan |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Request & |
res |
|
) |
| |
|
protected |
◆ getFootstepPose()
◆ initializeInteractiveMarker()
void FootstepMarker::initializeInteractiveMarker |
( |
| ) |
|
|
protected |
◆ lookGround()
void FootstepMarker::lookGround |
( |
| ) |
|
|
protected |
◆ makeFootstepMarker()
◆ menuCommandCB()
void FootstepMarker::menuCommandCB |
( |
const std_msgs::UInt8::ConstPtr & |
msg | ) |
|
|
protected |
◆ menuFeedbackCB()
void FootstepMarker::menuFeedbackCB |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
protected |
◆ moveMarkerCB()
void FootstepMarker::moveMarkerCB |
( |
const geometry_msgs::PoseStamped::ConstPtr & |
msg | ) |
|
|
protected |
◆ planDoneCB()
◆ planIfPossible()
void FootstepMarker::planIfPossible |
( |
| ) |
|
|
protected |
◆ processFeedbackCB()
void FootstepMarker::processFeedbackCB |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
protected |
◆ processMenuFeedback()
void FootstepMarker::processMenuFeedback |
( |
uint8_t |
id | ) |
|
|
protected |
◆ projectionCallback()
void FootstepMarker::projectionCallback |
( |
const geometry_msgs::PoseStamped & |
pose | ) |
|
|
protected |
◆ projectMarkerToPlane()
bool FootstepMarker::projectMarkerToPlane |
( |
| ) |
|
|
protected |
◆ readPoseParam()
◆ resetLegPoses()
void FootstepMarker::resetLegPoses |
( |
| ) |
|
|
protected |
◆ resumeCB()
void FootstepMarker::resumeCB |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
|
protected |
◆ resumeFootstep()
void FootstepMarker::resumeFootstep |
( |
| ) |
|
|
protected |
◆ snapLegs()
void FootstepMarker::snapLegs |
( |
| ) |
|
|
protected |
◆ updateInitialFootstep()
void FootstepMarker::updateInitialFootstep |
( |
| ) |
|
◆ ac_
◆ ac_exec_
◆ always_planning_
bool FootstepMarker::always_planning_ |
|
protected |
◆ current_pose_pub_
◆ estimate_occlusion_client_
◆ exec_sub_
◆ foot_size_x_
double FootstepMarker::foot_size_x_ |
|
protected |
◆ foot_size_y_
double FootstepMarker::foot_size_y_ |
|
protected |
◆ foot_size_z_
double FootstepMarker::foot_size_z_ |
|
protected |
◆ footstep_margin_
double FootstepMarker::footstep_margin_ |
|
protected |
◆ footstep_pub_
◆ initial_reference_frame_
◆ latest_grids_
jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr FootstepMarker::latest_grids_ |
|
protected |
◆ lfoot_frame_id_
◆ lleg_first_
bool FootstepMarker::lleg_first_ |
|
protected |
◆ lleg_initial_pose_
◆ lleg_offset_
◆ lleg_pose_
◆ marker_frame_id_
◆ marker_pose_
geometry_msgs::PoseStamped FootstepMarker::marker_pose_ |
|
protected |
◆ menu_command_sub_
◆ menu_handler_
◆ move_marker_sub_
◆ plan_if_possible_srv_
◆ plan_result_
PlanResult::ConstPtr FootstepMarker::plan_result_ |
|
protected |
◆ plan_run_
bool FootstepMarker::plan_run_ |
|
protected |
◆ plan_run_mutex_
◆ plane_mutex_
◆ project_footprint_pub_
◆ projection_sub_
◆ resume_sub_
◆ rfoot_frame_id_
◆ rleg_initial_pose_
◆ rleg_offset_
◆ rleg_pose_
◆ server_
◆ show_6dof_control_
bool FootstepMarker::show_6dof_control_ |
|
protected |
◆ snapit_client_
◆ snapped_pose_pub_
◆ srv_
std::shared_ptr<dynamic_reconfigure::Server<Config> > FootstepMarker::srv_ |
|
protected |
◆ tf_listener_
◆ use_2d_
bool FootstepMarker::use_2d_ |
|
protected |
◆ use_footstep_controller_
bool FootstepMarker::use_footstep_controller_ |
|
protected |
◆ use_footstep_planner_
bool FootstepMarker::use_footstep_planner_ |
|
protected |
◆ use_initial_footstep_tf_
bool FootstepMarker::use_initial_footstep_tf_ |
|
protected |
◆ use_initial_reference_
bool FootstepMarker::use_initial_reference_ |
|
protected |
◆ use_plane_snap_
bool FootstepMarker::use_plane_snap_ |
|
protected |
◆ use_projection_service_
bool FootstepMarker::use_projection_service_ |
|
protected |
◆ use_projection_topic_
bool FootstepMarker::use_projection_topic_ |
|
protected |
◆ wait_snapit_server_
bool FootstepMarker::wait_snapit_server_ |
|
protected |
The documentation for this class was generated from the following files: