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 _darwin_icra12_alg_node_h_
00026 #define _darwin_icra12_alg_node_h_
00027
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "darwin_icra12_alg.h"
00030 #include <tf/transform_listener.h>
00031
00032
00033 #include <geometry_msgs/PoseStamped.h>
00034
00035
00036
00037
00038 #include <control_msgs/FollowJointTrajectoryAction.h>
00039 #include <move_base_msgs/MoveBaseAction.h>
00040 #include <actionlib/client/simple_action_client.h>
00041 #include <actionlib/client/terminal_state.h>
00042 #include <arm_navigation_msgs/MoveArmAction.h>
00043
00044 typedef enum {detect_object=0,make_decision,move_robot,move_arms,open_gripper,close_gripper,cancel_motion} TStates;
00045
00050 class DarwinIcra12AlgNode : public algorithm_base::IriBaseAlgorithm<DarwinIcra12Algorithm>
00051 {
00052 private:
00053
00054
00055
00056 ros::Subscriber object_pose_subscriber_;
00057 void object_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg);
00058 geometry_msgs::PoseStamped object_pose;
00059 bool new_object_pose;
00060 CMutex object_pose_mutex_;
00061
00062
00063
00064
00065
00066
00067
00068
00069 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_right_arm_client_;
00070 arm_navigation_msgs::MoveArmGoal move_right_arm_goal_;
00071 void move_right_armMakeActionRequest();
00072 void move_right_armDone(const actionlib::SimpleClientGoalState& state, const arm_navigation_msgs::MoveArmResultConstPtr& result);
00073 void move_right_armActive();
00074 void move_right_armFeedback(const arm_navigation_msgs::MoveArmFeedbackConstPtr& feedback);
00075
00076 actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> move_joints_client_;
00077 control_msgs::FollowJointTrajectoryGoal move_joints_goal_;
00078 void move_jointsMakeActionRequest();
00079 void move_jointsDone(const actionlib::SimpleClientGoalState& state, const control_msgs::FollowJointTrajectoryResultConstPtr& result);
00080 void move_jointsActive();
00081 void move_jointsFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback);
00082
00083 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> move_base_client_;
00084 move_base_msgs::MoveBaseGoal move_base_goal_;
00085 void move_baseMakeActionRequest();
00086 void move_baseDone(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result);
00087 void move_baseActive();
00088 void move_baseFeedback(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
00089
00090 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_left_arm_client_;
00091 arm_navigation_msgs::MoveArmGoal move_left_arm_goal_;
00092 void move_left_armMakeActionRequest();
00093 void move_left_armDone(const actionlib::SimpleClientGoalState& state, const arm_navigation_msgs::MoveArmResultConstPtr& result);
00094 void move_left_armActive();
00095 void move_left_armFeedback(const arm_navigation_msgs::MoveArmFeedbackConstPtr& feedback);
00096
00097 tf::TransformListener tf_listener;
00098 bool arm_moving;
00099 bool base_moving;
00100 bool joints_moving;
00101
00102 TStates state;
00103
00104 public:
00111 DarwinIcra12AlgNode(void);
00112
00119 ~DarwinIcra12AlgNode(void);
00120
00121 protected:
00134 void mainNodeThread(void);
00135
00148 void node_config_update(Config &config, uint32_t level);
00149
00156 void addNodeDiagnostics(void);
00157
00158
00159
00160
00161 };
00162
00163 #endif