Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef IDENTIFICATIONNODE_HPP_
00035 #define IDENTIFICATIONNODE_HPP_
00036 #include <labust/control/SOIdentification.hpp>
00037 #include <labust/simulation/matrixfwd.hpp>
00038
00039 #include <auv_msgs/NavSts.h>
00040 #include <actionlib/server/simple_action_server.h>
00041 #include <navcon_msgs/DOFIdentificationAction.h>
00042 #include <ros/ros.h>
00043
00044 #include <Eigen/Dense>
00045
00046 namespace labust
00047 {
00048 namespace control
00049 {
00057 class IdentificationNode
00058 {
00059 enum {x=0,y,z,roll,pitch,yaw,altitude, u, v, w, measNum};
00060 enum {X=0,Y,Z,K,M,N};
00061 enum {alpha=0,beta,betaa};
00062
00063 typedef navcon_msgs::DOFIdentificationAction Action;
00064 typedef actionlib::SimpleActionServer<Action> ActionServer;
00065 typedef boost::shared_ptr<ActionServer> ActionServerPtr;
00066 typedef navcon_msgs::DOFIdentificationGoal Goal;
00067 typedef navcon_msgs::DOFIdentificationResult Result;
00068
00069 typedef Eigen::Matrix<double, measNum,1> MeasVec;
00070
00071 public:
00075 IdentificationNode();
00079 void onInit();
00080
00081 private:
00085 void onMeasurement(const auv_msgs::NavSts::ConstPtr& meas);
00089 void doIdentification(const Goal::ConstPtr& goal);
00093 void setTau(int elem, double value);
00094
00098 ros::Publisher tauOut, stateOut;
00102 ros::Subscriber meas;
00106 ActionServerPtr aserver;
00110 boost::thread identrunner;
00114 MeasVec measurements;
00121 bool integrateUV;
00127 bool useUV;
00133 bool useW;
00137 double cumulative_error;
00141 boost::mutex measmux;
00142 };
00143 }
00144 }
00145
00146
00147 #endif