#include <PlanFootsteps.h>
Public Types | |
typedef double | _costs_type |
typedef int64_t | _expanded_states_type |
typedef double | _final_eps_type |
typedef std::vector < ::humanoid_nav_msgs::StepTarget_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::humanoid_nav_msgs::StepTarget_ < ContainerAllocator > >::other > | _footsteps_type |
typedef double | _planning_time_type |
typedef uint8_t | _result_type |
typedef boost::shared_ptr < ::humanoid_nav_msgs::PlanFootstepsResponse_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::humanoid_nav_msgs::PlanFootstepsResponse_ < ContainerAllocator > > | Ptr |
typedef PlanFootstepsResponse_ < ContainerAllocator > | Type |
Public Member Functions | |
PlanFootstepsResponse_ () | |
PlanFootstepsResponse_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
double | costs |
int64_t | expanded_states |
double | final_eps |
std::vector < ::humanoid_nav_msgs::StepTarget_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::humanoid_nav_msgs::StepTarget_ < ContainerAllocator > >::other > | footsteps |
double | planning_time |
uint8_t | result |
Definition at line 61 of file PlanFootsteps.h.
typedef double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_costs_type |
Definition at line 90 of file PlanFootsteps.h.
typedef int64_t humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_expanded_states_type |
Definition at line 99 of file PlanFootsteps.h.
typedef double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_final_eps_type |
Definition at line 93 of file PlanFootsteps.h.
typedef std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_footsteps_type |
Definition at line 87 of file PlanFootsteps.h.
typedef double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_planning_time_type |
Definition at line 96 of file PlanFootsteps.h.
typedef uint8_t humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::_result_type |
Definition at line 84 of file PlanFootsteps.h.
typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> const> humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::ConstPtr |
Definition at line 104 of file PlanFootsteps.h.
typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::Ptr |
Definition at line 103 of file PlanFootsteps.h.
typedef PlanFootstepsResponse_<ContainerAllocator> humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::Type |
Definition at line 62 of file PlanFootsteps.h.
humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::PlanFootstepsResponse_ | ( | ) | [inline] |
Definition at line 64 of file PlanFootsteps.h.
humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::PlanFootstepsResponse_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 74 of file PlanFootsteps.h.
boost::shared_ptr<std::map<std::string, std::string> > humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::__connection_header |
Definition at line 105 of file PlanFootsteps.h.
double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::costs |
Definition at line 91 of file PlanFootsteps.h.
int64_t humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::expanded_states |
Definition at line 100 of file PlanFootsteps.h.
double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::final_eps |
Definition at line 94 of file PlanFootsteps.h.
std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::footsteps |
Definition at line 88 of file PlanFootsteps.h.
double humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::planning_time |
Definition at line 97 of file PlanFootsteps.h.
uint8_t humanoid_nav_msgs::PlanFootstepsResponse_< ContainerAllocator >::result |
Definition at line 85 of file PlanFootsteps.h.