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 #ifndef _kinton_vs_control_alg_node_h_
00026 #define _kinton_vs_control_alg_node_h_
00027
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "kinton_vs_control_alg.h"
00030
00031
00032 #include <geometry_msgs/TwistWithCovariance.h>
00033 #include <geometry_msgs/Twist.h>
00034 #include <nav_msgs/Odometry.h>
00035
00036 #include <std_msgs/Float64.h>
00037 #include <std_msgs/Bool.h>
00038 #include <asctec_msgs/LLStatus.h>
00039
00040 #include <bitset>
00041 #include <Eigen/Dense>
00042 #include <control_toolbox/pid.h>
00043
00044 #include <tf/transform_listener.h>
00045
00046
00047
00048
00049
00050
00055 class KintonVsControlAlgNode : public algorithm_base::IriBaseAlgorithm<KintonVsControlAlgorithm>
00056 {
00057 private:
00058
00059
00060 ros::Publisher cmd_yaw_publisher_;
00061 std_msgs::Float64 cmd_yaw_msg_;
00062 ros::Publisher cmd_pitch_publisher_;
00063 std_msgs::Float64 cmd_pitch_msg_;
00064 ros::Publisher cmd_roll_publisher_;
00065 std_msgs::Float64 cmd_roll_msg_;
00066 ros::Publisher cmd_thrust_publisher_;
00067 std_msgs::Float64 cmd_thrust_msg_;
00068
00069 ros::Publisher ESTOP_publisher_;
00070 std_msgs::Bool Bool_msg_;
00071
00072
00073
00074 ros::Subscriber cam_vel_subscriber_;
00075 void cam_vel_callback(const geometry_msgs::TwistWithCovariance::ConstPtr& msg);
00076 CMutex cam_vel_mutex_;
00077
00078 ros::Subscriber odom_subscriber_;
00079 void odom_callback(const nav_msgs::Odometry::ConstPtr& msg);
00080 CMutex odom_mutex_;
00081
00082 ros::Subscriber ll_status_subscriber_;
00083 void ll_status_callback(const asctec_msgs::LLStatus::ConstPtr& msg);
00084 CMutex ll_status_mutex_;
00085
00086 Eigen::MatrixXd cam_twist_;
00087
00088 bool activate_;
00089 bool estop_;
00090 bool serial_;
00091 bool marker_ctrl_;
00092
00093 double height_,height_fix_;
00094 double ctrl_ref_, sat_min_, sat_max_, trimm_x_, trimm_y_, rollpitch_sat_max_, rollpitch_sat_min_, yaw_sat_max_, yaw_sat_min_;
00095 double nm_thrust_kp_, nm_thrust_kd_, nm_roll_kp_, nm_roll_kd_, nm_pitch_kp_, nm_pitch_kd_, nm_yaw_kp_, nm_yaw_kd_;
00096 ros::Time time_, time_last_;
00097
00098
00099 control_toolbox::Pid nm_pid_roll_, nm_pid_pitch_, nm_pid_yaw_, nm_pid_thrust_;
00100
00101 Eigen::Matrix4d T_quad_to_cam_;
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112 public:
00119 KintonVsControlAlgNode(void);
00120
00127 ~KintonVsControlAlgNode(void);
00128
00129 protected:
00142 void mainNodeThread(void);
00143
00149 Eigen::MatrixXd cam_to_quad_vel();
00150
00156 Eigen::Matrix4d getTransform(const tf::StampedTransform& transform);
00157
00163 Eigen::MatrixXd signal_adapt(const Eigen::MatrixXd& cmd_raw);
00164
00177 void node_config_update(Config &config, uint32_t level);
00178
00185 void addNodeDiagnostics(void);
00186
00187
00188
00189
00190 };
00191
00192 #endif