manual_grasping_node.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * \file manual_grasping_node.h
00003  * \brief Node for manual grasping
00004  * \author Zdenek Materna (imaterna@fit.vutbr.cz)
00005  *
00006  * $Id:$
00007  *
00008  * Copyright (C) Brno University of Technology
00009  *
00010  * This file is part of software developed by dcgm-robotics@FIT group.
00011  *
00012  * Author: Zdenek Materna (imaterna@fit.vutbr.cz)
00013  * Supervised by: Michal Spanel (spanel@fit.vutbr.cz)
00014  * Date: dd/mm/2012
00015  *
00016  * This file is free software: you can redistribute it and/or modify
00017  * it under the terms of the GNU Lesser General Public License as published by
00018  * the Free Software Foundation, either version 3 of the License, or
00019  * (at your option) any later version.
00020  *
00021  * This file is distributed in the hope that it will be useful,
00022  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00023  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00024  * GNU Lesser General Public License for more details.
00025  *
00026  * You should have received a copy of the GNU Lesser General Public License
00027  * along with this file.  If not, see <http://www.gnu.org/licenses/>.
00028  */
00029 
00037 #pragma once
00038 #ifndef GRASPING_NODE_H
00039 #define GRASPING_NODE_H
00040 
00041 #include <ros/ros.h>
00042 #include <string>
00043 #include <math.h>
00044 
00045 #include <actionlib/server/simple_action_server.h>
00046 #include <actionlib/client/simple_action_client.h>
00047 
00048 #include "srs_assisted_grasping/services_list.h"
00049 #include "srs_assisted_grasping/topics_list.h"
00050 
00051 #include "srs_assisted_grasping_msgs/ReactiveGraspingAction.h"
00052 //#include <control_msgs/FollowJointTrajectoryAction.h>
00053 
00054 #include "std_msgs/MultiArrayLayout.h"
00055 #include "std_msgs/MultiArrayDimension.h"
00056 #include "std_msgs/Int32MultiArray.h"
00057 #include "std_msgs/Float32MultiArray.h"
00058 
00059 //#include "trajectory_msgs/JointTrajectory.h"
00060 #include "pr2_controllers_msgs/JointTrajectoryControllerState.h"
00061 
00062 #include "cob_srvs/SetOperationMode.h"
00063 #include "brics_actuator/JointVelocities.h"
00064 
00065 /*#include <boost/units/io.hpp>
00066 #include <boost/units/systems/angle/degrees.hpp>
00067 #include <boost/units/conversion.hpp>*/
00068 
00069 namespace srs_assisted_grasping {
00070 
00071 struct ReactiveGraspingParams {
00072 
00073     ros::Duration default_time_;
00074     double max_force_;
00075     double max_velocity_;
00076     double ramp_;
00077     double rate_;
00078 
00079 };
00080 
00081 struct Joints {
00082 
00083 
00084         std::vector<std::string> joints;
00085         std::vector<bool> has_tactile_pad;
00086 
00087 };
00088 
00089 
00090 class ReactiveGrasping {
00091 
00092 public:
00093 
00094     void TactileDataCallback(const std_msgs::Float32MultiArray::ConstPtr & msg);
00095     void SdhStateCallback(const pr2_controllers_msgs::JointTrajectoryControllerState::ConstPtr & msg);
00096 
00097 
00098 
00099     ReactiveGrasping(std::string name);
00100 
00101     ~ReactiveGrasping() {
00102 
00103       server_->shutdown();
00104       delete server_;
00105 
00106     };
00107 
00108 
00109 
00110 protected:
00111 
00112 
00113 
00114     ros::ServiceClient sdh_mode_client_; // for setting SDH to right mode
00115 
00116     ros::Subscriber tact_sub_; // for receiving tactile data
00117     ros::Subscriber state_sub_; // for receiving sdh state data
00118 
00119 
00120     actionlib::SimpleActionServer<srs_assisted_grasping_msgs::ReactiveGraspingAction> * server_;
00121 
00122     ros::NodeHandle nh_;
00123     std::string action_name_;
00124 
00125     boost::mutex data_mutex_;
00126 
00127 
00128     void execute(const srs_assisted_grasping_msgs::ReactiveGraspingGoalConstPtr &goal);
00129 
00130     ros::Publisher vel_publisher_;
00131 
00132     std_msgs::Float32MultiArray tactile_data_;
00133     pr2_controllers_msgs::JointTrajectoryControllerState sdh_data_;
00134 
00135     ros::Time tactile_data_stamp_;
00136 
00137     ReactiveGraspingParams params_;
00138     Joints joints_;
00139 
00140     bool setMode(std::string mode);
00141 
00142 private:
00143 
00144 
00145 
00146 
00147 };
00148 
00149 
00150 } // namespace
00151 
00152 
00153 #endif /* GRASPING_NODE_H */


srs_assisted_grasping
Author(s): Zdenek Materna
autogenerated on Mon Oct 6 2014 07:59:09