kinton_vs_control_alg_node.h
Go to the documentation of this file.
00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
00002 // Author 
00003 // All rights reserved.
00004 //
00005 // This file is part of iri-ros-pkg
00006 // iri-ros-pkg is free software: you can redistribute it and/or modify
00007 // it under the terms of the GNU Lesser General Public License as published by
00008 // the Free Software Foundation, either version 3 of the License, or
00009 // at your option) any later version.
00010 //
00011 // This program is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU Lesser General Public License for more details.
00015 //
00016 // You should have received a copy of the GNU Lesser General Public License
00017 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 // 
00019 // IMPORTANT NOTE: This code has been generated through a script from the 
00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
00021 // of the scripts. ROS topics can be easly add by using those scripts. Please
00022 // refer to the IRI wiki page for more information:
00023 // http://wikiri.upc.es/index.php/Robotics_Lab
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 // [publisher subscriber headers]
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 // [service client headers]
00048 
00049 // [action server client headers]
00050 
00055 class KintonVsControlAlgNode : public algorithm_base::IriBaseAlgorithm<KintonVsControlAlgorithm>
00056 {
00057   private:
00058     // [publisher attributes]
00059     // Control commands 4DOF
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     //Emergency Stop
00069     ros::Publisher ESTOP_publisher_;
00070     std_msgs::Bool Bool_msg_;
00071 
00072     // [subscriber attributes]
00073     //Camera velocity
00074     ros::Subscriber cam_vel_subscriber_;
00075     void cam_vel_callback(const geometry_msgs::TwistWithCovariance::ConstPtr& msg);
00076     CMutex cam_vel_mutex_;
00077     //Odometry
00078     ros::Subscriber odom_subscriber_;
00079     void odom_callback(const nav_msgs::Odometry::ConstPtr& msg);
00080     CMutex odom_mutex_;
00081     //Low level Kinton Information (to check serial switch)
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_; //Actual velocity of the camera from the visual servo
00087 
00088     bool activate_; //Activates the servoing
00089     bool estop_; //Emergency stop
00090     bool serial_; //Serial enabled
00091     bool marker_ctrl_; //Indicates that cam velocities are correct from the marker (marker visible)
00092 
00093     double height_,height_fix_; //Current Height and Height reference in case of height control
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     //No marker control PIDs (Height control)
00099     control_toolbox::Pid nm_pid_roll_, nm_pid_pitch_, nm_pid_yaw_, nm_pid_thrust_; 
00100 
00101     Eigen::Matrix4d T_quad_to_cam_; //Homogenous transform between Quadrotor and camera frames
00102 
00103 
00104     // [service attributes]
00105 
00106     // [client attributes]
00107 
00108     // [action server attributes]
00109 
00110     // [action client attributes]
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     // [diagnostic functions]
00188     
00189     // [test functions]
00190 };
00191 
00192 #endif


kinton_vs_control
Author(s): asantamaria
autogenerated on Fri Dec 6 2013 23:24:19