labjack_node.h
Go to the documentation of this file.
00001 #ifndef __LABJACK_NODE_H__
00002 #define __LABJACK_NODE_H__
00003 
00029 #include "ljacklm_wrapper.h"
00030 #include "labjack_data.h"
00031 
00032 // messages and services
00033 #include <basic_states_skill_msgs/States.h>
00034 #include <basic_states_skill_msgs/GetLabjackState.h>
00035 #include <basic_states_skill_msgs/SetLabjackState.h>
00036 #include <batteries_skill_msgs/LabjackBatteryInfo.h>
00037 #include <batteries_skill_msgs/LabjackPlugInfo.h>
00038 #include <touch_skill_msgs/LabjackTouchInfo.h>
00039 
00040 class LabjackNode {
00041     public:
00045         LabjackNode(LabjackDriverInterface *ljdriver);
00046 
00050         ~LabjackNode();
00051 
00055         void init();
00056 
00060         void spin();
00061 
00063         // publishers
00065 
00069         void publish_touch();
00070 
00074         void publish_battery();
00075 
00079         void publish_state();
00080 
00082         // services
00084 
00091         bool getTouchSensors(touch_skill_msgs::LabjackTouchInfo::Request & req,
00092                              touch_skill_msgs::LabjackTouchInfo::Response & resp);
00093 
00100         bool getPower(batteries_skill_msgs::LabjackBatteryInfo::Request & req,
00101                       batteries_skill_msgs::LabjackBatteryInfo::Response & resp);
00102 
00109         bool getIsPlugged(batteries_skill_msgs::LabjackPlugInfo::Request & req,
00110                           batteries_skill_msgs::LabjackPlugInfo::Response & resp);
00111 
00118         bool getStates(basic_states_skill_msgs::GetLabjackState::Request & req,
00119                        basic_states_skill_msgs::GetLabjackState::Response & resp);
00120 
00127         bool setStates(basic_states_skill_msgs::SetLabjackState::Request & req,
00128                        basic_states_skill_msgs::SetLabjackState::Response & resp);
00129 
00131         // methods
00133 
00141         t_ljdata getAll();
00142 
00143         // low level methods
00144 
00149         float getStateDs();
00150 
00156         int setStateDs(long stateD);
00157 
00163         int getStateD(long stateD);
00164 
00170         int setStateD(long stateD);
00171 
00177         int clearStateD(long stateD);
00178 
00183         long getDsDirection();
00184 
00189         float getStateIOs();
00190 
00196         int setStateIOs(long stateIO);
00197 
00203         int getStateIO(long stateIO);
00204 
00210         int setStateIO(long stateIO);
00211 
00217         int clearStateIO(long stateIO);
00218 
00223         float8 getAIs();
00224 
00230         float getAI(long channel);
00231 
00237         int setAOs(float2 voltageAO);
00238 
00244         int setPulseD(t_pulseData data);
00245 
00251         int setPulseIO(t_pulseData data);
00252 
00253         // states methods
00254 
00259         int getState();
00260 
00266         int setState(int state);
00267 
00273         int enableBase(bool enable);
00274 
00280         int enableBody(bool enable);
00281 
00286         int setWatchdog();
00287 
00292         int clearWatchdog();
00293 
00298         int isEmergency();
00299 
00304         int setEmergency();
00305 
00306         // sensors methods
00307 
00312         float getVoltage();
00313 
00318         bool isPlugged();
00319 
00324         touch getTouch();
00325 
00326     private:
00327         // nodes
00328         ros::NodeHandle _nh;
00329         ros::NodeHandle _nh_private;
00330 
00331         // services
00332         ros::ServiceServer _touch_srv;
00333         ros::ServiceServer _get_voltage_srv;
00334         ros::ServiceServer _get_is_plugged_srv;
00335         ros::ServiceServer _get_state_srv;
00336         ros::ServiceServer _set_state_srv;
00337 
00338         // spin rate
00339         ros::Rate _publish_rate;
00340 
00341         t_ljdata _labjack_data;
00342         LabjackDriverInterface *_ljdriver;
00343 };
00344 
00345 #endif


labjack
Author(s): Raul Perula-Martinez
autogenerated on Wed Apr 1 2015 10:17:06