52 int main(
int argc,
char** argv){
53 ros::init(argc, argv,
"humanoid_planner_2d");
void goalCallback(const geometry_msgs::PoseStampedConstPtr &goal)
Set goal and plan when start was already set.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber goal_sub_
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancy_map)
calls updateMap()
ros::Subscriber start_sub_
virtual ~SBPLPlanner2DNode()
void startCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &start)
Set start and plan when goal was already set.
int main(int argc, char **argv)