Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
FootstepMarker Class Reference

#include <footstep_marker.h>

List of all members.

Public Types

typedef
jsk_interactive_marker::FootstepMarkerConfig 
Config
typedef
actionlib::SimpleActionClient
< jsk_footstep_msgs::ExecFootstepsAction > 
ExecuteActionClient
typedef
actionlib::SimpleActionClient
< jsk_footstep_msgs::PlanFootstepsAction > 
PlanningActionClient
typedef
jsk_footstep_msgs::PlanFootstepsResult 
PlanResult

Public Member Functions

 FootstepMarker ()
void updateInitialFootstep ()
virtual ~FootstepMarker ()

Protected Member Functions

void callEstimateOcclusion ()
void cancelWalk ()
void changePlannerHeuristic (const std::string &heuristic)
geometry_msgs::Pose computeLegTransformation (uint8_t leg)
geometry_msgs::Polygon computePolygon (uint8_t leg)
void configCallback (Config &config, uint32_t level)
void executeCB (const std_msgs::Empty::ConstPtr &msg)
void executeFootstep ()
bool forceToReplan (std_srvs::Empty::Request &req, std_srvs::Empty::Request &res)
geometry_msgs::Pose getFootstepPose (bool leftp)
void initializeInteractiveMarker ()
void lookGround ()
visualization_msgs::Marker makeFootstepMarker (geometry_msgs::Pose pose)
void menuCommandCB (const std_msgs::UInt8::ConstPtr &msg)
void menuFeedbackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void moveMarkerCB (const geometry_msgs::PoseStamped::ConstPtr &msg)
void planDoneCB (const actionlib::SimpleClientGoalState &state, const PlanResult::ConstPtr &result)
void planIfPossible ()
void processFeedbackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void processMenuFeedback (uint8_t id)
void projectionCallback (const geometry_msgs::PoseStamped &pose)
bool projectMarkerToPlane ()
void readPoseParam (ros::NodeHandle &pnh, const std::string param, tf::Transform &offset)
void resetLegPoses ()
void resumeCB (const std_msgs::Empty::ConstPtr &msg)
void resumeFootstep ()
void snapLegs ()

Protected Attributes

PlanningActionClient ac_
ExecuteActionClient ac_exec_
bool always_planning_
ros::Publisher current_pose_pub_
ros::ServiceClient estimate_occlusion_client_
ros::Subscriber exec_sub_
double foot_size_x_
double foot_size_y_
double foot_size_z_
double footstep_margin_
ros::Publisher footstep_pub_
std::string initial_reference_frame_
jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr latest_grids_
std::string lfoot_frame_id_
bool lleg_first_
geometry_msgs::Pose lleg_initial_pose_
tf::Transform lleg_offset_
geometry_msgs::Pose lleg_pose_
std::string marker_frame_id_
geometry_msgs::PoseStamped marker_pose_
ros::Subscriber menu_command_sub_
interactive_markers::MenuHandler menu_handler_
ros::Subscriber move_marker_sub_
ros::ServiceServer plan_if_possible_srv_
PlanResult::ConstPtr plan_result_
bool plan_run_
boost::mutex plan_run_mutex_
boost::mutex plane_mutex_
ros::Publisher project_footprint_pub_
ros::Subscriber projection_sub_
ros::Subscriber resume_sub_
std::string rfoot_frame_id_
geometry_msgs::Pose rleg_initial_pose_
tf::Transform rleg_offset_
geometry_msgs::Pose rleg_pose_
std::shared_ptr
< interactive_markers::InteractiveMarkerServer
server_
bool show_6dof_control_
ros::ServiceClient snapit_client_
ros::Publisher snapped_pose_pub_
std::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
std::shared_ptr
< tf::TransformListener
tf_listener_
bool use_2d_
bool use_footstep_controller_
bool use_footstep_planner_
bool use_initial_footstep_tf_
bool use_initial_reference_
bool use_plane_snap_
bool use_projection_service_
bool use_projection_topic_
bool wait_snapit_server_

Detailed Description

Definition at line 64 of file footstep_marker.h.


Member Typedef Documentation

typedef jsk_interactive_marker::FootstepMarkerConfig FootstepMarker::Config

Definition at line 66 of file footstep_marker.h.

typedef actionlib::SimpleActionClient<jsk_footstep_msgs::ExecFootstepsAction> FootstepMarker::ExecuteActionClient

Definition at line 73 of file footstep_marker.h.

typedef actionlib::SimpleActionClient<jsk_footstep_msgs::PlanFootstepsAction> FootstepMarker::PlanningActionClient

Definition at line 71 of file footstep_marker.h.

typedef jsk_footstep_msgs::PlanFootstepsResult FootstepMarker::PlanResult

Definition at line 74 of file footstep_marker.h.


Constructor & Destructor Documentation

Definition at line 57 of file footstep_marker.cpp.

Definition at line 834 of file footstep_marker.cpp.


Member Function Documentation

Definition at line 486 of file footstep_marker.cpp.

void FootstepMarker::cancelWalk ( ) [protected]

Definition at line 479 of file footstep_marker.cpp.

void FootstepMarker::changePlannerHeuristic ( const std::string heuristic) [protected]

Definition at line 467 of file footstep_marker.cpp.

Definition at line 297 of file footstep_marker.cpp.

geometry_msgs::Polygon FootstepMarker::computePolygon ( uint8_t  leg) [protected]

Definition at line 334 of file footstep_marker.cpp.

void FootstepMarker::configCallback ( Config config,
uint32_t  level 
) [protected]

Definition at line 224 of file footstep_marker.cpp.

void FootstepMarker::executeCB ( const std_msgs::Empty::ConstPtr &  msg) [protected]

Definition at line 367 of file footstep_marker.cpp.

void FootstepMarker::executeFootstep ( ) [protected]

Definition at line 599 of file footstep_marker.cpp.

bool FootstepMarker::forceToReplan ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Request &  res 
) [protected]

Definition at line 416 of file footstep_marker.cpp.

Definition at line 692 of file footstep_marker.cpp.

Definition at line 759 of file footstep_marker.cpp.

void FootstepMarker::lookGround ( ) [protected]

Definition at line 405 of file footstep_marker.cpp.

visualization_msgs::Marker FootstepMarker::makeFootstepMarker ( geometry_msgs::Pose  pose) [protected]

Definition at line 748 of file footstep_marker.cpp.

void FootstepMarker::menuCommandCB ( const std_msgs::UInt8::ConstPtr &  msg) [protected]

Definition at line 375 of file footstep_marker.cpp.

void FootstepMarker::menuFeedbackCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 540 of file footstep_marker.cpp.

void FootstepMarker::moveMarkerCB ( const geometry_msgs::PoseStamped::ConstPtr &  msg) [protected]

Definition at line 724 of file footstep_marker.cpp.

void FootstepMarker::planDoneCB ( const actionlib::SimpleClientGoalState state,
const PlanResult::ConstPtr &  result 
) [protected]

Definition at line 681 of file footstep_marker.cpp.

void FootstepMarker::planIfPossible ( ) [protected]

Definition at line 623 of file footstep_marker.cpp.

void FootstepMarker::processFeedbackCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 544 of file footstep_marker.cpp.

void FootstepMarker::processMenuFeedback ( uint8_t  id) [protected]

Definition at line 422 of file footstep_marker.cpp.

void FootstepMarker::projectionCallback ( const geometry_msgs::PoseStamped &  pose) [protected]

Definition at line 582 of file footstep_marker.cpp.

Definition at line 492 of file footstep_marker.cpp.

void FootstepMarker::readPoseParam ( ros::NodeHandle pnh,
const std::string  param,
tf::Transform offset 
) [protected]

Definition at line 247 of file footstep_marker.cpp.

void FootstepMarker::resetLegPoses ( ) [protected]

Definition at line 279 of file footstep_marker.cpp.

void FootstepMarker::resumeCB ( const std_msgs::Empty::ConstPtr &  msg) [protected]

Definition at line 371 of file footstep_marker.cpp.

void FootstepMarker::resumeFootstep ( ) [protected]

Definition at line 568 of file footstep_marker.cpp.

void FootstepMarker::snapLegs ( ) [protected]

Definition at line 325 of file footstep_marker.cpp.

Definition at line 379 of file footstep_marker.cpp.


Member Data Documentation

Definition at line 142 of file footstep_marker.h.

Definition at line 143 of file footstep_marker.h.

Definition at line 154 of file footstep_marker.h.

Definition at line 136 of file footstep_marker.h.

Definition at line 139 of file footstep_marker.h.

Definition at line 131 of file footstep_marker.h.

double FootstepMarker::foot_size_x_ [protected]

Definition at line 123 of file footstep_marker.h.

double FootstepMarker::foot_size_y_ [protected]

Definition at line 124 of file footstep_marker.h.

double FootstepMarker::foot_size_z_ [protected]

Definition at line 125 of file footstep_marker.h.

Definition at line 126 of file footstep_marker.h.

Definition at line 137 of file footstep_marker.h.

Definition at line 157 of file footstep_marker.h.

jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr FootstepMarker::latest_grids_ [protected]

Definition at line 104 of file footstep_marker.h.

Definition at line 164 of file footstep_marker.h.

bool FootstepMarker::lleg_first_ [protected]

Definition at line 155 of file footstep_marker.h.

Definition at line 160 of file footstep_marker.h.

Definition at line 162 of file footstep_marker.h.

Definition at line 158 of file footstep_marker.h.

Definition at line 127 of file footstep_marker.h.

geometry_msgs::PoseStamped FootstepMarker::marker_pose_ [protected]

Definition at line 128 of file footstep_marker.h.

Definition at line 130 of file footstep_marker.h.

Definition at line 122 of file footstep_marker.h.

Definition at line 129 of file footstep_marker.h.

Definition at line 140 of file footstep_marker.h.

PlanResult::ConstPtr FootstepMarker::plan_result_ [protected]

Definition at line 168 of file footstep_marker.h.

bool FootstepMarker::plan_run_ [protected]

Definition at line 149 of file footstep_marker.h.

Definition at line 99 of file footstep_marker.h.

Definition at line 98 of file footstep_marker.h.

Definition at line 134 of file footstep_marker.h.

Definition at line 133 of file footstep_marker.h.

Definition at line 132 of file footstep_marker.h.

Definition at line 165 of file footstep_marker.h.

Definition at line 161 of file footstep_marker.h.

Definition at line 163 of file footstep_marker.h.

Definition at line 159 of file footstep_marker.h.

Definition at line 121 of file footstep_marker.h.

Definition at line 146 of file footstep_marker.h.

Definition at line 138 of file footstep_marker.h.

Definition at line 135 of file footstep_marker.h.

std::shared_ptr<dynamic_reconfigure::Server<Config> > FootstepMarker::srv_ [protected]

Definition at line 100 of file footstep_marker.h.

Definition at line 141 of file footstep_marker.h.

bool FootstepMarker::use_2d_ [protected]

Definition at line 156 of file footstep_marker.h.

Definition at line 148 of file footstep_marker.h.

Definition at line 147 of file footstep_marker.h.

Definition at line 152 of file footstep_marker.h.

Definition at line 153 of file footstep_marker.h.

Definition at line 150 of file footstep_marker.h.

Definition at line 144 of file footstep_marker.h.

Definition at line 145 of file footstep_marker.h.

Definition at line 151 of file footstep_marker.h.


The documentation for this class was generated from the following files:


jsk_interactive_marker
Author(s): furuta
autogenerated on Wed May 1 2019 02:40:31