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 _uncalibvs_sim_alg_node_h_
00026 #define _uncalibvs_sim_alg_node_h_
00027
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "uncalibvs_sim_alg.h"
00030
00031
00032 #include <sensor_msgs/JointState.h>
00033 #include <gazebo_msgs/ModelStates.h>
00034 #include <geometry_msgs/Twist.h>
00035 #include <ar_pose/ARMarkers.h>
00036
00037
00038
00039
00040 #include <actionlib/client/simple_action_client.h>
00041 #include <actionlib/client/terminal_state.h>
00042
00043 #include <tf/transform_listener.h>
00044 #include <kdl_parser/kdl_parser.hpp>
00045
00046
00047
00052 class Uncalibvs_simAlgNode : public algorithm_base::IriBaseAlgorithm<Uncalibvs_simAlgorithm>
00053 {
00054 private:
00055
00056 ros::Publisher joints_pub_publisher_;
00057 sensor_msgs::JointState JointState_msg_;
00058 ros::Publisher output_publisher_,output_publisher_pose_;
00059 geometry_msgs::Twist Twist_msg_;
00060
00061
00062 ros::Subscriber model_state_subscriber_;
00063 void model_state_callback(const gazebo_msgs::ModelStates::ConstPtr& msg);
00064 CMutex model_state_mutex_;
00065 void input_tag_callback(const ar_pose::ARMarkers::ConstPtr& msg);
00066 CMutex input_tag_mutex_;
00067 ros::Subscriber input_tag_subscriber_;
00068
00069
00070 Uncalibvs_simAlgorithm uncalib_vs_sim_alg;
00071
00072 bool mutex, init_, ini_vars_;
00073 geometry_msgs::Pose pose_;
00074 geometry_msgs::Twist twist_quad_;
00075
00076 ros::Time t_,t_old_;
00077
00078
00079 bool activate_,traditional_,random_points_,quadrotor_,output_files_,arm_unina_,arm_catec_;
00080 double lambda_,dist_to_tag_,fixed_to_id_;
00081 int num_joints_;
00082 std::string path_;
00083
00084 KDL::Chain kdl_chain_;
00085 Eigen::MatrixXf q_,lambda_robot_;
00086 Eigen::Matrix3f Rquad_inertial_;
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098 public:
00105 Uncalibvs_simAlgNode(void);
00106
00113 ~Uncalibvs_simAlgNode(void);
00114
00115 protected:
00128 void mainNodeThread(void);
00129
00142 void node_config_update(Config &config, uint32_t level);
00143
00150 void addNodeDiagnostics(void);
00151
00152
00153
00154
00155 };
00156
00157 #endif