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

#include <footstep_marker.h>

List of all members.

Public Types

typedef
actionlib::SimpleActionClient
< jsk_footstep_msgs::ExecFootstepsAction > 
ExecuteActionClient
typedef
message_filters::sync_policies::ExactTime
< jsk_pcl_ros::PolygonArray,
jsk_pcl_ros::ModelCoefficientsArray > 
PlaneSyncPolicy
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 ()
geometry_msgs::Pose computeLegTransformation (uint8_t leg)
geometry_msgs::Polygon computePolygon (uint8_t leg)
void executeCB (const std_msgs::Empty::ConstPtr &msg)
void executeFootstep ()
geometry_msgs::Pose getFootstepPose (bool leftp)
void initializeInteractiveMarker ()
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 planeCB (const jsk_pcl_ros::PolygonArray::ConstPtr &planes, const jsk_pcl_ros::ModelCoefficientsArray::ConstPtr &coefficients)
void planIfPossible ()
void processFeedbackCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void processMenuFeedback (uint8_t id)
bool projectMarkerToPlane ()
double projectPoseToPlane (const std::vector< geometry_msgs::PointStamped > &polygon, const geometry_msgs::PoseStamped &point, geometry_msgs::PoseStamped &foot)
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 ()
void transformPolygon (const geometry_msgs::PolygonStamped &polygon, const std_msgs::Header &target_header, std::vector< geometry_msgs::PointStamped > &output_points)

Protected Attributes

PlanningActionClient ac_
ExecuteActionClient ac_exec_
message_filters::Subscriber
< jsk_pcl_ros::ModelCoefficientsArray > 
coefficients_sub_
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_pcl_ros::ModelCoefficientsArray::ConstPtr latest_coefficients_
jsk_pcl_ros::PolygonArray::ConstPtr latest_planes_
std::string lfoot_frame_id_
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_
PlanResult::ConstPtr plan_result_
bool plan_run_
boost::mutex plan_run_mutex_
boost::mutex plane_mutex_
message_filters::Subscriber
< jsk_pcl_ros::PolygonArray > 
polygons_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_
boost::shared_ptr
< interactive_markers::InteractiveMarkerServer
server_
bool show_6dof_control_
ros::ServiceClient snapit_client_
ros::Publisher snapped_pose_pub_
boost::shared_ptr
< message_filters::Synchronizer
< PlaneSyncPolicy > > 
sync_
boost::shared_ptr
< tf::TransformListener
tf_listener_
bool use_footstep_controller_
bool use_footstep_planner_
bool use_initial_footstep_tf_
bool use_initial_reference_
bool use_plane_snap_
bool wait_snapit_server_

Detailed Description

Definition at line 27 of file footstep_marker.h.


Member Typedef Documentation

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

Definition at line 37 of file footstep_marker.h.

typedef message_filters::sync_policies::ExactTime< jsk_pcl_ros::PolygonArray, jsk_pcl_ros::ModelCoefficientsArray> FootstepMarker::PlaneSyncPolicy

Definition at line 33 of file footstep_marker.h.

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

Definition at line 35 of file footstep_marker.h.

typedef jsk_footstep_msgs::PlanFootstepsResult FootstepMarker::PlanResult

Definition at line 38 of file footstep_marker.h.


Constructor & Destructor Documentation

Definition at line 15 of file footstep_marker.cpp.

Definition at line 756 of file footstep_marker.cpp.


Member Function Documentation

Definition at line 360 of file footstep_marker.cpp.

void FootstepMarker::cancelWalk ( ) [protected]

Definition at line 353 of file footstep_marker.cpp.

Definition at line 208 of file footstep_marker.cpp.

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

Definition at line 245 of file footstep_marker.cpp.

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

Definition at line 278 of file footstep_marker.cpp.

void FootstepMarker::executeFootstep ( ) [protected]

Definition at line 545 of file footstep_marker.cpp.

Definition at line 619 of file footstep_marker.cpp.

Definition at line 686 of file footstep_marker.cpp.

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

Definition at line 675 of file footstep_marker.cpp.

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

Definition at line 286 of file footstep_marker.cpp.

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

Definition at line 505 of file footstep_marker.cpp.

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

Definition at line 651 of file footstep_marker.cpp.

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

Definition at line 608 of file footstep_marker.cpp.

void FootstepMarker::planeCB ( const jsk_pcl_ros::PolygonArray::ConstPtr &  planes,
const jsk_pcl_ros::ModelCoefficientsArray::ConstPtr &  coefficients 
) [protected]

Definition at line 759 of file footstep_marker.cpp.

void FootstepMarker::planIfPossible ( ) [protected]

Definition at line 569 of file footstep_marker.cpp.

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

Definition at line 509 of file footstep_marker.cpp.

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

Definition at line 311 of file footstep_marker.cpp.

Definition at line 465 of file footstep_marker.cpp.

double FootstepMarker::projectPoseToPlane ( const std::vector< geometry_msgs::PointStamped > &  polygon,
const geometry_msgs::PoseStamped &  point,
geometry_msgs::PoseStamped &  foot 
) [protected]

Definition at line 366 of file footstep_marker.cpp.

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

Definition at line 158 of file footstep_marker.cpp.

void FootstepMarker::resetLegPoses ( ) [protected]

Definition at line 190 of file footstep_marker.cpp.

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

Definition at line 282 of file footstep_marker.cpp.

void FootstepMarker::resumeFootstep ( ) [protected]

Definition at line 531 of file footstep_marker.cpp.

void FootstepMarker::snapLegs ( ) [protected]

Definition at line 236 of file footstep_marker.cpp.

void FootstepMarker::transformPolygon ( const geometry_msgs::PolygonStamped &  polygon,
const std_msgs::Header target_header,
std::vector< geometry_msgs::PointStamped > &  output_points 
) [protected]

Definition at line 447 of file footstep_marker.cpp.

Definition at line 290 of file footstep_marker.cpp.


Member Data Documentation

Definition at line 109 of file footstep_marker.h.

Definition at line 110 of file footstep_marker.h.

message_filters::Subscriber<jsk_pcl_ros::ModelCoefficientsArray> FootstepMarker::coefficients_sub_ [protected]

Definition at line 101 of file footstep_marker.h.

Definition at line 107 of file footstep_marker.h.

Definition at line 98 of file footstep_marker.h.

double FootstepMarker::foot_size_x_ [protected]

Definition at line 90 of file footstep_marker.h.

double FootstepMarker::foot_size_y_ [protected]

Definition at line 91 of file footstep_marker.h.

double FootstepMarker::foot_size_z_ [protected]

Definition at line 92 of file footstep_marker.h.

Definition at line 93 of file footstep_marker.h.

Definition at line 105 of file footstep_marker.h.

Definition at line 119 of file footstep_marker.h.

jsk_pcl_ros::ModelCoefficientsArray::ConstPtr FootstepMarker::latest_coefficients_ [protected]

Definition at line 73 of file footstep_marker.h.

jsk_pcl_ros::PolygonArray::ConstPtr FootstepMarker::latest_planes_ [protected]

Definition at line 72 of file footstep_marker.h.

Definition at line 126 of file footstep_marker.h.

Definition at line 122 of file footstep_marker.h.

Definition at line 124 of file footstep_marker.h.

Definition at line 120 of file footstep_marker.h.

Definition at line 94 of file footstep_marker.h.

geometry_msgs::PoseStamped FootstepMarker::marker_pose_ [protected]

Definition at line 95 of file footstep_marker.h.

Definition at line 97 of file footstep_marker.h.

Definition at line 89 of file footstep_marker.h.

Definition at line 96 of file footstep_marker.h.

PlanResult::ConstPtr FootstepMarker::plan_result_ [protected]

Definition at line 130 of file footstep_marker.h.

bool FootstepMarker::plan_run_ [protected]

Definition at line 115 of file footstep_marker.h.

Definition at line 61 of file footstep_marker.h.

Definition at line 60 of file footstep_marker.h.

message_filters::Subscriber<jsk_pcl_ros::PolygonArray> FootstepMarker::polygons_sub_ [protected]

Definition at line 100 of file footstep_marker.h.

Definition at line 99 of file footstep_marker.h.

Definition at line 127 of file footstep_marker.h.

Definition at line 123 of file footstep_marker.h.

Definition at line 125 of file footstep_marker.h.

Definition at line 121 of file footstep_marker.h.

Definition at line 88 of file footstep_marker.h.

Definition at line 111 of file footstep_marker.h.

Definition at line 106 of file footstep_marker.h.

Definition at line 104 of file footstep_marker.h.

Definition at line 102 of file footstep_marker.h.

boost::shared_ptr<tf::TransformListener> FootstepMarker::tf_listener_ [protected]

Definition at line 108 of file footstep_marker.h.

Definition at line 113 of file footstep_marker.h.

Definition at line 112 of file footstep_marker.h.

Definition at line 117 of file footstep_marker.h.

Definition at line 118 of file footstep_marker.h.

Definition at line 114 of file footstep_marker.h.

Definition at line 116 of file footstep_marker.h.


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


jsk_interactive_marker
Author(s): furuta
autogenerated on Mon Oct 6 2014 01:19:15