dynamixel_no_gripper_driver.cpp
Go to the documentation of this file.
00001 #include "dynamixel_no_gripper_driver.h"
00002 #include <stdlib.h>
00003 #include <sys/types.h>
00004 #include <sys/stat.h>
00005 #include <unistd.h>
00006 #include <dirent.h>
00007 
00008 std::string config_path = std::string("/config/");
00009 
00010 DynamixelNoGripperDriver::DynamixelNoGripperDriver(void):
00011     // dynamixel attributes (default values)
00012     gripper_config_file_(std::string("gripper_no_config.xml")),
00013     xml_path_(std::string(".")),
00014     full_path_(xml_path_ + config_path + gripper_config_file_)
00015 {
00016     //setDriverId(driver string id);
00017 }
00018 
00019 DynamixelNoGripperDriver::~DynamixelNoGripperDriver(void)
00020 {
00021 }
00022 
00023 void DynamixelNoGripperDriver::scan_XML_files(void)
00024 {
00025   std::string full_path;
00026   struct dirent *dp;
00027   struct stat st;
00028   DIR *dir;
00029 
00030   full_path=this->xml_path_ + config_path;
00031   // check wether the config XML files folder exists or not
00032   if(stat(full_path.c_str(),&st)==0)// the folder exists
00033   {
00034     dir=opendir(full_path.c_str());
00035     while((dp=readdir(dir)) != NULL)
00036     {
00037       if(strstr(dp->d_name,".xml")!=NULL)
00038         this->full_path_ = full_path + dp->d_name;
00039     }
00040     closedir(dir);
00041   }
00042   ROS_INFO("Found gripper configuration file %s in %s", gripper_config_file_.c_str(), full_path.c_str());
00043 }
00044 
00045 bool DynamixelNoGripperDriver::openDriver(void)
00046 {
00047     bool result(false);
00048     try
00049     {
00050         this->lock();
00051         this->gripper_ = boost::shared_ptr<CDynamixelGripper>(new CDynamixelGripper());
00052         std::cout << full_path_ << std::endl;
00053         gripper_->load_config(this->full_path_);
00054         std::cout << *gripper_ << std::endl;
00055         this->unlock();
00056         result = true;
00057     }
00058     catch(CException &e)
00059     {
00060         std::cout << e.what() << std::endl;
00061         ROS_INFO("Impossible to configure the Gripper with the given parameters");
00062         this->unlock();
00063         result = false;
00064     }
00065     return result;
00066 }
00067 
00068 bool DynamixelNoGripperDriver::closeDriver(void)
00069 {
00070     return true;
00071 }
00072 
00073 bool DynamixelNoGripperDriver::startDriver(void)
00074 {
00075     return true;
00076 }
00077 
00078 bool DynamixelNoGripperDriver::stopDriver(void)
00079 {
00080     return true;
00081 }
00082 
00083 void DynamixelNoGripperDriver::config_update(Config& new_cfg, uint32_t level)
00084 {
00085     this->lock();
00086 
00087     // depending on current state
00088     // update driver with new_cfg data
00089     switch(this->getState())
00090     {
00091         case DynamixelNoGripperDriver::CLOSED:
00092             // save the values into the class
00093             this->xml_path_ = new_cfg.XML_path;
00094             this->scan_XML_files();
00095             this->full_path_ = this->xml_path_ + config_path + new_cfg.config_file;
00096             break;
00097 
00098         case DynamixelNoGripperDriver::OPENED:
00099             break;
00100 
00101         case DynamixelNoGripperDriver::RUNNING:
00102             try
00103             {
00104                 // set the torque
00105             }
00106             catch(CDynamixelMotorException &e)
00107             {
00108                 ROS_ERROR("%s",e.what().c_str());
00109             }
00110             break;
00111     }
00112 
00113     // save the current configuration
00114     this->config_ = new_cfg;
00115 
00116     this->unlock();
00117 }
00118 
00119 
00120 bool DynamixelNoGripperDriver::open_gripper(void)
00121 {
00122     return this->gripper_->open_gripper();
00123 }
00124 
00125 bool DynamixelNoGripperDriver::close_gripper()
00126 {
00127     return this->gripper_->close_gripper();
00128 }
00129 
00130 void DynamixelNoGripperDriver::stop_gripper()
00131 {
00132     if (this->getState() != DynamixelNoGripperDriver::CLOSED)
00133     {
00134         try
00135         {
00136               this->gripper_->disable();
00137         }     
00138         catch (CDynamixelMotorException &e)
00139         {
00140             ROS_ERROR("%s", e.what().c_str());
00141         }   
00142     }   
00143 }
00144 
00145 float DynamixelNoGripperDriver::get_current_effort()
00146 {
00147     return this->gripper_->get_current_effort();
00148 }   
00149 
00150 float DynamixelNoGripperDriver::get_current_angle()
00151 {
00152     return this->gripper_->get_current_angle();
00153 }   
00154 
00155 bool DynamixelNoGripperDriver::is_at_max_angle()
00156 {
00157     return this->gripper_->is_gripper_opened();
00158     
00159 }   
00160 
00161 bool DynamixelNoGripperDriver::is_at_min_angle()
00162 {
00163     return this->gripper_->is_gripper_closed();
00164 }   
00165 
00166 void DynamixelNoGripperDriver::disable_gripper()
00167 {
00168     this->gripper_->disable();
00169 }   
00170 


iri_dynamixel_no_gripper
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 20:00:46