qnode.hpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009 ** Ifdefs
00010 *****************************************************************************/
00011 
00012 #ifndef tibi_dabo_sequence_editor_QNODE_HPP_
00013 #define tibi_dabo_sequence_editor_QNODE_HPP_
00014 
00015 /*****************************************************************************
00016 ** Includes
00017 *****************************************************************************/
00018 
00019 #include <ros/ros.h>
00020 // [publisher subscriber headers]
00021 #include <sensor_msgs/JointState.h>
00022 
00023 // [action server client headers]
00024 #include <actionlib/client/simple_action_client.h>
00025 #include <actionlib/client/terminal_state.h>
00026 #include <control_msgs/FollowJointTrajectoryAction.h>
00027 
00028 // GUI
00029 #include <string>
00030 #include <QThread>
00031 #include <QStringListModel>
00032 
00033 #include "mutex.h"
00034 #include "eventserver.h"
00035 #include "motion_sequence.h"
00036 
00037 /*****************************************************************************
00038 ** Namespaces
00039 *****************************************************************************/
00040 
00041 namespace tibi_dabo_sequence_editor {
00042 
00043 typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> SeqClient;
00044 
00045 typedef struct
00046 {
00047   SeqClient *client;
00048   bool succeeded;
00049   bool active;
00050   bool loaded;
00051   float percentage;
00052 }TSeqClient;
00053 
00054 /*****************************************************************************
00055 ** Class
00056 *****************************************************************************/
00057 
00058 class QNode : public QThread 
00059 {
00060   Q_OBJECT
00061   public:
00062     QNode(int argc, char** argv );
00063     ~QNode();
00064     void run();
00065     void get_motion_feedback(std::vector<float> &position, std::vector<float> &velocity);
00066     std::vector<std::string> get_config_files(void);
00067     bool is_connected(void);
00068     std::string get_new_feedback_event_id(void);
00069     std::string get_action_feedback_event_id(void);
00070     void execute_sequence(std::vector<TMotionStep> &seq);
00071 
00072   signals:
00073     void rosShutdown();
00074 
00075   private:
00076     // [subscriber attributes]
00077     ros::Subscriber motion_feedback_subscriber_;
00078     void motion_feedback_callback(const sensor_msgs::JointState::ConstPtr& msg);
00079     std::vector<float> position;
00080     std::vector<float> velocity;
00081     CMutex motion_feedback_mutex_;
00082 
00083     // motion sequence
00084     TSeqClient motion_;
00085     void motionMakeActionRequest(const control_msgs::FollowJointTrajectoryGoal & motion_goal);
00086     void motionDone(const actionlib::SimpleClientGoalState& state, const control_msgs::FollowJointTrajectoryResultConstPtr& result);
00087     void motionActive(void);
00088     void motionFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback);
00089 
00090     // parameter values
00091     std::vector<std::string> config_files;
00092     CEventServer *event_server;
00093     std::string new_feedback_event_id;
00094     std::string action_feedback_event_id;
00095 };
00096 
00097 }  // namespace tibi_dabo_sequence_editor
00098 
00099 #endif /* tibi_dabo_sequence_editor_QNODE_HPP_ */


tibi_dabo_sequence_editor
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 23:02:16