1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859 |
- #ifndef __PLANNING__H___
- #define __PLANNING__H___
- #include <ros/ros.h>
- #include <nav_msgs/GetPlan.h>
- #include <geometry_msgs/PoseStamped.h>
- #include <tf/transform_broadcaster.h>
- #include <tf/tf.h>
- #include "tf2_msgs/TFMessage.h"
- #include <Eigen/Core>
- #include <Eigen/Dense>
- #include <string>
- #include <boost/foreach.hpp>
- #include <boost/thread.hpp>
- #define forEach BOOST_FOREACH
- class Planning
- {
- public:
- Planning();
- ~Planning();
- bool Init();
- bool Make_plan(double x0,double y0,double x1,double y1);
- bool Make_plan(tf::Transform start,tf::Transform target);
- protected:
-
- private:
-
-
- static void tf_callback(const tf2_msgs::TFMessage::ConstPtr& msg,Planning* p);
- static void thread_publish_path(Planning* plan);
- public:
- ros::NodeHandle nh_;
- ros::Publisher path_publisher_;
- ros::Publisher path_publisher_left_;
- ros::Publisher path_publisher_right_;
- nav_msgs::Path path_;
- nav_msgs::Path path_left_;
- nav_msgs::Path path_right_;
- ros::ServiceClient make_plan_client_;
- ros::Subscriber tf_sub_;
- boost::thread* plan_publisher_thread_;
- boost::mutex mutex_path_;
- tf::Transform target_;
- tf::Transform start_pos_;
-
-
- };
- #endif
|