00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: teleop_cob_marker.h 2037 2012-11-30 16:28:17Z spanel $ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by Robo@FIT group. 00009 * 00010 * Author: Zdenek Materna (imaterna@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 1/12/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #ifndef TELEOPCOBSPACENAV_H_ 00029 #define TELEOPCOBSPACENAV_H_ 00030 00031 #include <ros/ros.h> 00032 #include <geometry_msgs/Twist.h> 00033 #include <tf/transform_datatypes.h> 00034 #include <sensor_msgs/Joy.h> 00035 #include <geometry_msgs/Vector3.h> 00036 #include <boost/signals2/mutex.hpp> 00037 #include <std_srvs/Empty.h> 00038 #include <tf/transform_listener.h> 00039 #include <Eigen/Core> 00040 #include <Eigen/Geometry> 00041 00042 namespace cob_spacenav_teleop 00043 { 00044 00045 struct Params { 00046 00047 00048 double max_vel_x; 00049 double max_vel_y; 00050 double max_vel_th; 00051 00052 double scale_linear; 00053 double scale_angular; 00054 00055 double sn_max_val; 00056 double sn_min_val_th; 00057 00058 bool use_rviz_cam; 00059 std::string rviz_cam_link; 00060 std::string robot_base_link; 00061 00062 double publish_rate; 00063 00064 bool instant_stop_enabled; 00065 00066 double ignore_th_high; 00067 double ignore_th_low; 00068 00069 bool unsafe_limiter; 00070 00071 }; 00072 00073 struct SpacenavData { 00074 00075 geometry_msgs::Vector3 offset; 00076 geometry_msgs::Vector3 rot_offset; 00077 00078 bool offset_received; 00079 bool rot_offset_received; 00080 00081 boost::signals2::mutex mutex; 00082 00083 ros::Time last_data; 00084 ros::Time last_nonzero_data; 00085 00086 }; 00087 00088 struct Buttons { 00089 00090 boost::signals2::mutex mutex; 00091 00092 bool left; 00093 bool right; 00094 bool right_last; 00095 bool right_trigger; 00096 }; 00097 00098 00099 class SpaceNavTeleop 00100 { 00101 public: 00102 00103 SpaceNavTeleop(); 00104 ~SpaceNavTeleop(); 00105 00106 bool transf(std::string target_frame,geometry_msgs::PoseStamped& pose); 00107 00108 protected: 00109 00110 ros::Subscriber offset_sub_; 00111 ros::Subscriber rot_offset_sub_; 00112 00113 Params params_; 00114 00115 void spacenavOffsetCallback(const geometry_msgs::Vector3ConstPtr& offset); 00116 void spacenavRotOffsetCallback(const geometry_msgs::Vector3ConstPtr& rot_offset); 00117 00118 void timerCallback(const ros::TimerEvent& ev); 00119 ros::Timer timer_; 00120 00121 void tfTimerCallback(const ros::TimerEvent& ev); 00122 ros::Timer tf_timer_; 00123 00124 ros::Publisher twist_publisher_safe_; 00125 ros::Publisher twist_publisher_unsafe_; 00126 00127 SpacenavData sn_data_; 00128 00129 00130 bool stop_detected_; 00131 ros::Time time_of_stop_; 00132 00133 bool enabled_; 00134 ros::ServiceServer service_en_; 00135 ros::ServiceServer service_dis_; 00136 00137 bool Enable(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res); 00138 bool Disable(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res); 00139 00140 tf::TransformListener *tfl_; 00141 00142 geometry_msgs::PoseStamped bp_; 00143 00144 00145 geometry_msgs::Vector3 GetAsEuler(geometry_msgs::Quaternion quat); 00146 void normAngle(double& a); 00147 00148 //bool some_dir_limited_; 00149 bool x_pref_; 00150 bool y_pref_; 00151 bool z_pref_; 00152 00153 ros::Time pref_time_; 00154 00155 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy); 00156 ros::Subscriber joy_sub_; 00157 bool publishing_to_unsafe_; 00158 bool robot_centric_mode_; 00159 00160 Buttons btns_; 00161 00162 private: 00163 00164 }; 00165 00166 } 00167 00168 #endif /* TELEOPCOBSPACENAV_H_ */