33 #include <hector_nav_msgs/GetRobotTrajectory.h> 53 hector_nav_msgs::GetRobotTrajectory::Response &res )
55 ROS_INFO(
"Exploration Service called");
60 geometry_msgs::PoseStamped pose;
63 res.trajectory.header.frame_id =
"map";
83 int main(
int argc,
char **argv) {
costmap_2d::Costmap2DROS * costmap_2d_ros_
bool explorationServiceCallback(hector_nav_msgs::GetRobotTrajectory::Request &req, hector_nav_msgs::GetRobotTrajectory::Response &res)
void publish(const boost::shared_ptr< M > &message) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
ros::Publisher exploration_plan_pub_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
tf::TransformListener tfl_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer exploration_plan_service_server_
ROSCPP_DECL void spin(Spinner &spinner)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
int main(int argc, char **argv)
SimpleExplorationPlanner()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
bool doExploration(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
hector_exploration_planner::HectorExplorationPlanner * planner_