00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2012 University of Osnabrück 00004 * 00005 * This program is free software; you can redistribute it and/or 00006 * modify it under the terms of the GNU General Public License 00007 * as published by the Free Software Foundation; either version 2 00008 * of the License, or (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00018 * 00019 * joint_commander.h 00020 * 00021 * Created on: 24.08.2012 00022 * Author: Martin Günther <mguenthe@uos.de> 00023 */ 00024 00025 #ifndef JOINT_COMMANDER_H_ 00026 #define JOINT_COMMANDER_H_ 00027 00028 #include <ros/ros.h> 00029 00030 #include <dynamic_reconfigure/server.h> 00031 #include <calvin_joint_commander/JointCommanderConfig.h> 00032 00033 #include <std_msgs/Float64.h> 00034 #include <sensor_msgs/JointState.h> 00035 00036 namespace calvin_joint_commander 00037 { 00038 00039 class JointCommander 00040 { 00041 public: 00042 JointCommander(); 00043 virtual ~JointCommander(); 00044 void update_config(calvin_joint_commander::JointCommanderConfig &new_config, uint32_t level = 0); 00045 void loop_once(); 00046 00047 private: 00048 // ROS 00049 ros::NodeHandle nh_; 00050 ros::Publisher kinect_pitch_controller_pub_; 00051 ros::Publisher webcam_pitch_controller_pub_; 00052 ros::Publisher joint_states_pub_; 00053 00054 // Dynamic Reconfigure 00055 JointCommanderConfig config_; 00056 dynamic_reconfigure::Server<calvin_joint_commander::JointCommanderConfig> dynamic_reconfigure_server_; 00057 00058 }; 00059 00060 } /* namespace kurtana_pole_joint_commander */ 00061 #endif /* JOINT_COMMANDER_H_ */