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 #ifndef _uncalibvs_alg_node_h_
00026 #define _uncalibvs_alg_node_h_
00027
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "uncalibvs_alg.h"
00030
00031
00032 #include <iri_uncalibvs/control.h>
00033 #include <asctec_msgs/LLStatus.h>
00034 #include <mav_msgs/Height.h>
00035 #include <sensor_msgs/Imu.h>
00036 #include <mav_msgs/Status.h>
00037 #include <std_msgs/Float64.h>
00038 #include <std_msgs/Bool.h>
00039 #include <asctec_msgs/CtrlInput.h>
00040 #include <asctec_msgs/ControllerOutput.h>
00041 #include <asctec_msgs/IMUCalcData.h>
00042
00043
00044 #include <geometry_msgs/Twist.h>
00045 #include <ar_pose/ARMarkers.h>
00046
00047 #include <bitset>
00048 #include <tf/transform_listener.h>
00049 #include <kdl_parser/kdl_parser.hpp>
00050
00051 #include <control_toolbox/pid.h>
00052
00053
00054
00055
00056
00057
00062 class UncalibvsAlgNode : public algorithm_base::IriBaseAlgorithm<Uncalibvs_Algorithm>
00063 {
00064 private:
00065
00066 ros::Publisher body_twist_publisher_;
00067 geometry_msgs::Twist body_twist_msg_;
00068 ros::Publisher yaw_control_publisher_;
00069 iri_uncalibvs::control yaw_control_msg_;
00070 ros::Publisher pitch_control_publisher_;
00071 iri_uncalibvs::control pitch_control_msg_;
00072 ros::Publisher roll_control_publisher_;
00073 iri_uncalibvs::control roll_control_msg_;
00074 ros::Publisher thrust_control_publisher_;
00075 iri_uncalibvs::control thrust_control_msg_;
00076 ros::Publisher state_publisher_;
00077 mav_msgs::Status Status_msg_;
00078 ros::Publisher cmd_yaw_publisher_;
00079 std_msgs::Float64 cmd_yaw_msg_;
00080 ros::Publisher cmd_pitch_publisher_;
00081 std_msgs::Float64 cmd_pitch_msg_;
00082 ros::Publisher cmd_roll_publisher_;
00083 std_msgs::Float64 cmd_roll_msg_;
00084 ros::Publisher cmd_thrust_publisher_;
00085 std_msgs::Float64 cmd_thrust_msg_;
00086 ros::Publisher ESTOP_publisher_;
00087 std_msgs::Bool Bool_msg_;
00088 geometry_msgs::Twist twist_quad_,twist_quad_asctec_,twist_ctrl_out_;
00089
00090
00091 ros::Subscriber ll_status_subscriber_;
00092 void ll_status_callback(const asctec_msgs::LLStatus::ConstPtr& msg);
00093 CMutex ll_status_mutex_;
00094 ros::Subscriber height_subscriber_;
00095 void height_callback(const mav_msgs::Height::ConstPtr& msg);
00096 CMutex height_mutex_;
00097 ros::Subscriber imu_subscriber_;
00098 void imu_callback(const sensor_msgs::Imu::ConstPtr& msg);
00099 CMutex imu_mutex_;
00100 ros::Subscriber model_state_subscriber_;
00101 void model_state_callback(const asctec_msgs::IMUCalcData::ConstPtr& msg);
00102 CMutex model_state_mutex_;
00103 void input_tag_callback(const ar_pose::ARMarkers::ConstPtr& msg);
00104 CMutex input_tag_mutex_;
00105 ros::Subscriber input_tag_subscriber_;
00106
00107 Uncalibvs_Algorithm uncalib_vs_alg_;
00108
00109 bool init_,activate_,traditional_,random_points_,quadrotor_,output_files_,estop_,serial_,calibrated_ctrl_;
00110
00111 double lambda_,final_z_,ENUyaw_,ENUyaw_fix_,height_,height_fix_,tag_thrust_kp_,tag_thrust_kd_,tag_roll_kp_,tag_roll_kd_,tag_pitch_kp_,tag_pitch_kd_,tag_yaw_kp_,tag_yaw_kd_,thrust_kp_,thrust_kd_,roll_kp_,roll_kd_,pitch_kp_,pitch_kd_,yaw_kp_,yaw_kd_,sat_min_,sat_max_,rollpitch_sat_min_,rollpitch_sat_max_,yaw_sat_min_,yaw_sat_max_,ctrl_ref_,angle_pitch_,angle_roll_,trimm_y_,trimm_x_,buff_speed_;
00112
00113 std::string path_;
00114
00115 control_toolbox::Pid tag_pid_thrust_,tag_pid_roll_,tag_pid_pitch_,tag_pid_yaw_,pid_thrust_,pid_roll_,pid_pitch_,pid_yaw_;
00116
00117 ros::Time time_,time_last_;
00118
00119 int rollpitch_div_;
00120
00121 Eigen::Matrix3f Rquad_inertial_;
00122 Eigen::MatrixXf tag_error_,error_;
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 public:
00141 UncalibvsAlgNode(void);
00142
00149 ~UncalibvsAlgNode(void);
00150
00151 protected:
00164 void mainNodeThread(void);
00165
00178 void node_config_update(Config &config, uint32_t level);
00179
00186 void addNodeDiagnostics(void);
00187
00188
00189
00190
00191 };
00192
00193 #endif