wam_controller_driver.h
Go to the documentation of this file.
00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
00002 // Author 
00003 // All rights reserved.
00004 //
00005 // This file is part of iri-ros-pkg
00006 // iri-ros-pkg is free software: you can redistribute it and/or modify
00007 // it under the terms of the GNU Lesser General Public License as published by
00008 // the Free Software Foundation, either version 3 of the License, or
00009 // at your option) any later version.
00010 //
00011 // This program is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU Lesser General Public License for more details.
00015 //
00016 // You should have received a copy of the GNU Lesser General Public License
00017 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 // 
00019 // IMPORTANT NOTE: This code has been generated through a script from the 
00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
00021 // of the scripts. ROS topics can be easly add by using those scripts. Please
00022 // refer to the IRI wiki page for more information:
00023 // http://wikiri.upc.es/index.php/Robotics_Lab
00024 
00025 #ifndef _wam_controller_driver_h_
00026 #define _wam_controller_driver_h_
00027 
00028 #include <iri_base_driver/iri_base_driver.h>
00029 #include <iri_wam_controller/WamControllerConfig.h>
00030 #include <trajectory_msgs/JointTrajectory.h> 
00031 
00032 //include wam_controller_driver main library
00033 #include "wamdriver.h"
00034 
00035 const bool HOLDON(true);
00036 const bool HOLDOFF(false);
00037 
00057 class WamControllerDriver : public iri_base_driver::IriBaseDriver
00058 {
00059   private:
00060     // private attributes and methods
00061     std::string robot_name_; 
00062     wamDriver *wam_; 
00063     trajectory_msgs::JointTrajectoryPoint desired_joint_trajectory_point_;  
00064   public:
00071     typedef iri_wam_controller::WamControllerConfig Config;
00072 
00079     Config config_;
00080 
00089     WamControllerDriver(void);
00090 
00101     bool openDriver(void);
00102 
00113     bool closeDriver(void);
00114 
00125     bool startDriver(void);
00126 
00137     bool stopDriver(void);
00138 
00150     void config_update(Config& new_cfg, uint32_t level=0);
00151 
00152     // here define all wam_controller_driver interface methods to retrieve and set
00153     // the driver parameters
00154 
00161     ~WamControllerDriver(void);
00162     
00163     
00164     void get_pose(std::vector<double> *pose);
00165     void get_joint_angles(std::vector<double> *angles);
00166 
00167     std::string get_robot_name(); 
00168     inline size_t get_num_joints() {return NJOINTS;};
00172     bool is_joints_move_request_valid(const std::vector<double> & angles);
00173 
00177     bool is_moving();
00178     bool is_joint_trajectory_result_succeeded();
00179 
00184     trajectory_msgs::JointTrajectoryPoint get_desired_joint_trajectory_point();
00185 
00192     void move_trajectory_in_joints(const trajectory_msgs::JointTrajectory & trajectory);
00193     void stop_trajectory_in_joints();
00194     void move_in_joints(std::vector<double> *angles, std::vector<double>* vels = NULL, std::vector<double>* accs = NULL);
00195     void wait_move_end();
00196     void hold_on();
00197     void hold_off();
00201     bool is_moving_trajectory();
00202  };
00203 
00204 #endif


iri_wam_controller
Author(s): galenya
autogenerated on Fri Dec 6 2013 20:08:29