aaa

Dependencies:   mbed BNO055_fusion Adafruit_GFX ros_lib_kinetic

Revision:
1:bdd17feaa4ce
Parent:
0:10f626cf3ec4
Child:
3:a45557a0dcb8
--- a/myRos.h	Thu Dec 06 10:22:27 2018 +0000
+++ b/myRos.h	Fri Dec 07 20:59:56 2018 +0000
@@ -1,48 +1,71 @@
 #ifndef _MY_ROS_H_
 #define _MY_ROS_H_
 
-#include "mbed.h"
-#include "ros.h"
-#include "ros/time.h"
-#include "std_msgs/Bool.h"
+#include "type.h"
+#include "odom.h"
+
+#include <mbed.h>
+#include <ros.h>
+#include <ros/time.h>
+#include <std_msgs/Bool.h>
+#include <geometry_msgs/Point.h>
+#include <geometry_msgs/PointStamped.h>
+#include <std_msgs/Empty.h>
 
 #define COURT_RED   false
 #define COURT_BLUE  true
 
-class myRos
+void ack_from_pc_cb(const std_msgs::Empty&);
+
+class My_Ros : public Odom_Abstract
 {
+    public:
+    
     private:
-    ros::NodeHandle nh_;
-    bool court_color_;
-//    std_msgs::Bool court_color_msg_;
-//    ros::Publisher court_color_pub_;
+        ros::NodeHandle nh_;
+        bool court_color_;
+        Vec3f initial_pose_;
+        Vec3f pose_;            //current position(odom -> base_footprint)
         
     public:
-    //Constructor
-    myRos(bool court_color = COURT_RED) : court_color_(court_color){
-        //ROS node initialize
-        nh_.getHardware()->setBaud(115200);
-        nh_.initNode();
+        //Constructor
+        My_Ros() : court_color_(COURT_RED){
+            //ROS node initialize
+            nh_.getHardware()->setBaud(115200);
+            nh_.initNode();
+            
+            initialize();
+        }
         
-//        initialize();
-
-//        court_color_pub_ = new ros::Publisher("court_color", &court_color_msg_);
-//        nh_.advertise(court_color_pub_);
-    }
-    
-    void loop(){
-        publisher();
-        nh_.spinOnce();
-//        court_color_msg_.data = court_color_;
-//        court_color_pub_.publish(&court_color_msg_);
-    }
-    
+        //Loop function
+        void loop();
+                
+        //Setter
+        void set_initial_pose(Vec3f initial_pose){
+           initial_pose_ = initial_pose;
+        }
+        void set_court_color(bool court_color){
+            court_color_ = court_color;   
+        }
+        template<typename SubscriberT>
+        void set_subscliber(SubscriberT& s){
+            nh_.subscribe(s);
+        }
+        
+        //amcl parameter の初期化
+        void enable_initialize_amcl();
+        
     private:
-    //Initialise
-    void initialize();
-    void publisher();
-    
-    
+        //Initialise
+        void initialize();
+        
+        //Publisher
+        void court_color_publisher();
+        void initial_pose_publisher();
+        void pose_publisher();
+        
+        //Amcl parameter
+        void set_amcl_parameter();
 };
 
 #endif
\ No newline at end of file