#include <footstep_marker.h>
Definition at line 27 of file footstep_marker.h.
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.
Definition at line 15 of file footstep_marker.cpp.
FootstepMarker::~FootstepMarker | ( | ) | [virtual] |
Definition at line 756 of file footstep_marker.cpp.
void FootstepMarker::callEstimateOcclusion | ( | ) | [protected] |
Definition at line 360 of file footstep_marker.cpp.
void FootstepMarker::cancelWalk | ( | ) | [protected] |
Definition at line 353 of file footstep_marker.cpp.
geometry_msgs::Pose FootstepMarker::computeLegTransformation | ( | uint8_t | leg | ) | [protected] |
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.
geometry_msgs::Pose FootstepMarker::getFootstepPose | ( | bool | leftp | ) | [protected] |
Definition at line 619 of file footstep_marker.cpp.
void FootstepMarker::initializeInteractiveMarker | ( | ) | [protected] |
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.
bool FootstepMarker::projectMarkerToPlane | ( | ) | [protected] |
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.
PlanningActionClient FootstepMarker::ac_ [protected] |
Definition at line 109 of file footstep_marker.h.
ExecuteActionClient FootstepMarker::ac_exec_ [protected] |
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.
ros::Subscriber FootstepMarker::exec_sub_ [protected] |
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.
double FootstepMarker::footstep_margin_ [protected] |
Definition at line 93 of file footstep_marker.h.
ros::Publisher FootstepMarker::footstep_pub_ [protected] |
Definition at line 105 of file footstep_marker.h.
std::string FootstepMarker::initial_reference_frame_ [protected] |
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.
std::string FootstepMarker::lfoot_frame_id_ [protected] |
Definition at line 126 of file footstep_marker.h.
Definition at line 122 of file footstep_marker.h.
tf::Transform FootstepMarker::lleg_offset_ [protected] |
Definition at line 124 of file footstep_marker.h.
geometry_msgs::Pose FootstepMarker::lleg_pose_ [protected] |
Definition at line 120 of file footstep_marker.h.
std::string FootstepMarker::marker_frame_id_ [protected] |
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.
ros::Subscriber FootstepMarker::menu_command_sub_ [protected] |
Definition at line 97 of file footstep_marker.h.
Definition at line 89 of file footstep_marker.h.
ros::Subscriber FootstepMarker::move_marker_sub_ [protected] |
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.
boost::mutex FootstepMarker::plan_run_mutex_ [protected] |
Definition at line 61 of file footstep_marker.h.
boost::mutex FootstepMarker::plane_mutex_ [protected] |
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.
ros::Subscriber FootstepMarker::resume_sub_ [protected] |
Definition at line 99 of file footstep_marker.h.
std::string FootstepMarker::rfoot_frame_id_ [protected] |
Definition at line 127 of file footstep_marker.h.
Definition at line 123 of file footstep_marker.h.
tf::Transform FootstepMarker::rleg_offset_ [protected] |
Definition at line 125 of file footstep_marker.h.
geometry_msgs::Pose FootstepMarker::rleg_pose_ [protected] |
Definition at line 121 of file footstep_marker.h.
boost::shared_ptr<interactive_markers::InteractiveMarkerServer> FootstepMarker::server_ [protected] |
Definition at line 88 of file footstep_marker.h.
bool FootstepMarker::show_6dof_control_ [protected] |
Definition at line 111 of file footstep_marker.h.
ros::ServiceClient FootstepMarker::snapit_client_ [protected] |
Definition at line 106 of file footstep_marker.h.
ros::Publisher FootstepMarker::snapped_pose_pub_ [protected] |
Definition at line 104 of file footstep_marker.h.
boost::shared_ptr<message_filters::Synchronizer<PlaneSyncPolicy> > FootstepMarker::sync_ [protected] |
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.
bool FootstepMarker::use_footstep_controller_ [protected] |
Definition at line 113 of file footstep_marker.h.
bool FootstepMarker::use_footstep_planner_ [protected] |
Definition at line 112 of file footstep_marker.h.
bool FootstepMarker::use_initial_footstep_tf_ [protected] |
Definition at line 117 of file footstep_marker.h.
bool FootstepMarker::use_initial_reference_ [protected] |
Definition at line 118 of file footstep_marker.h.
bool FootstepMarker::use_plane_snap_ [protected] |
Definition at line 114 of file footstep_marker.h.
bool FootstepMarker::wait_snapit_server_ [protected] |
Definition at line 116 of file footstep_marker.h.