iri_joystick_driver.cpp
Go to the documentation of this file.
00001 #include "iri_joystick_driver.h"
00002 #include <iridrivers/exceptions.h>
00003 
00004 IriJoystickDriver::IriJoystickDriver() :
00005     dev_("/dev/input/js0"),
00006     pub_channel_name_("joy")
00007 {
00008   //setDriverId(driver string id);
00009     pid_t pid = getpid();
00010     std::ostringstream s;
00011     s << "iri_joystick" << pid;
00012 
00013     try
00014     {
00015         jh_  = new CJoystick(s.str());
00016     }
00017     catch(CException &e)
00018     {
00019         ROS_FATAL("'%s'",e.what().c_str());
00020     }
00021 }
00022 
00023 bool IriJoystickDriver::openDriver(void)
00024 {
00025     try
00026     {
00027         jh_->open(dev_);
00028         ROS_DEBUG("Joystick found at '%s'", dev_.c_str());
00029     }
00030     catch(CException &e)
00031     {
00032         ROS_ERROR("Open failed with: '%s'",e.what().c_str());
00033         return false;
00034     }
00035 
00036     return true;
00037 }
00038 
00039 bool IriJoystickDriver::closeDriver(void)
00040 {
00041     try
00042     {
00043         jh_->close();
00044     }
00045     catch (CException & e)
00046     {
00047         ROS_ERROR("'%s'",e.what().c_str());
00048         return false;
00049     }
00050 
00051     return true;
00052 }
00053 
00054 bool IriJoystickDriver::startDriver(void)
00055 {
00056   return true;
00057 }
00058 
00059 bool IriJoystickDriver::stopDriver(void)
00060 {
00061   return true;
00062 }
00063 
00064 void IriJoystickDriver::config_update(const Config& new_cfg, uint32_t level)
00065 {
00066   this->lock();
00067 
00068   //update driver with new_cfg data
00069 
00070   // save the current configuration
00071   this->config_=new_cfg;
00072 
00073   this->unlock();
00074 }
00075 
00076 void
00077 IriJoystickDriver::enable_position_change_callback(int axis_id,
00078                          void (* callback) (void * param, unsigned int axis_id, float value),
00079                          void * param)
00080 {
00081     jh_->enable_position_change_callback(axis_id, callback, param);
00082 }
00083 
00084 void
00085 IriJoystickDriver::enable_button_callback(int button_id,
00086                          void (* callback) (void * param, unsigned int button_id, bool level),
00087                          void * param)
00088 {
00089     jh_->enable_button_callback(button_id, callback, param);
00090 }
00091 
00092 int
00093 IriJoystickDriver::get_num_buttons() const
00094 {
00095     return jh_->get_num_buttons();
00096 }
00097 
00098 int
00099 IriJoystickDriver::get_num_axes() const
00100 {
00101     return jh_->get_num_axis();
00102 }
00103 
00104 std::string
00105 IriJoystickDriver::get_device() const
00106 {
00107     return dev_;
00108 }
00109 
00110 IriJoystickDriver::~IriJoystickDriver()
00111 {
00112     delete(jh_);
00113 }


iri_joystick
Author(s): Jose Luis Rivero
autogenerated on Fri Dec 6 2013 23:38:45