Public Member Functions | Private Attributes
LabjackNode Class Reference

#include <labjack_node.h>

List of all members.

Public Member Functions

int clearStateD (long stateD)
 Function which assign a value of 0 to the D line specified in the parameter.
int clearStateIO (long stateIO)
 Function which clear the state of one IO line.
int clearWatchdog ()
 Function which clear the watchog.
int enableBase (bool enable)
 Function which enable the base to move.
int enableBody (bool enable)
 Function which enable the body to move.
float getAI (long channel)
 Function which get the value of one AI line.
float8 getAIs ()
 Function which get the value of the AI lines.
t_ljdata getAll ()
 Function which return all data relative to the labjack. Digital and analog lines. These lines have connected: touch sensors, batteries, state of the emergency button RF, state of the emergency button of Maggie, control signal of motor in the base and control signal of the other motors.
long getDsDirection ()
 Function which return the directions of the D lines: 0 is an input and 1 an output.
bool getIsPlugged (batteries_skill_msgs::LabjackPlugInfo::Request &req, batteries_skill_msgs::LabjackPlugInfo::Response &resp)
 Callback to get the information of the batteries.
bool getPower (batteries_skill_msgs::LabjackBatteryInfo::Request &req, batteries_skill_msgs::LabjackBatteryInfo::Response &resp)
 Callback to get the information of the batteries.
int getState ()
 Function which get the current state.
int getStateD (long stateD)
 Function which return the state of a specific D line.
float getStateDs ()
 Function which return the state of all D lines.
int getStateIO (long stateIO)
 Function which get the state of one IO line.
float getStateIOs ()
 Function which get the state of the IO lines.
bool getStates (basic_states_skill_msgs::GetLabjackState::Request &req, basic_states_skill_msgs::GetLabjackState::Response &resp)
 Callback to get the information of the states.
touch getTouch ()
 Function which get the value of the touch sensors.
bool getTouchSensors (touch_skill_msgs::LabjackTouchInfo::Request &req, touch_skill_msgs::LabjackTouchInfo::Response &resp)
 Callback to get the information of the touch sensors.
float getVoltage ()
 Function which return the value in volts of the battery.
void init ()
 Initialize the labjack node.
int isEmergency ()
 Function which get if the labjack is in emergency state.
bool isPlugged ()
 Function which return the state of the robot connection.
 LabjackNode (LabjackDriverInterface *ljdriver)
 Empty constructor.
void publish_battery ()
 Publish information from the battery.
void publish_state ()
 Publish information from the states.
void publish_touch ()
 Publish information from the touch sensors.
int setAOs (float2 voltageAO)
 Function which assign a voltage. If only one parameter desire, pass negative value to the other.
int setEmergency ()
 Function which emergency by software.
int setPulseD (t_pulseData data)
 Function which write a pulse in a D line.
int setPulseIO (t_pulseData data)
 Function which write a pulse in a IO line.
int setState (int state)
 Function which set the state.
int setStateD (long stateD)
 Function which assign a value of 1 to the D line specified in the parameter.
int setStateDs (long stateD)
 Function which assing a new state to all D lines.
int setStateIO (long stateIO)
 Function which set the state of one IO line.
int setStateIOs (long stateIO)
 Function which set the state of the IO lines.
bool setStates (basic_states_skill_msgs::SetLabjackState::Request &req, basic_states_skill_msgs::SetLabjackState::Response &resp)
 Callback to set a state.
int setWatchdog ()
 Function which set the watchdog.
void spin ()
 Spin the node.
 ~LabjackNode ()
 Destructor.

Private Attributes

ros::ServiceServer _get_is_plugged_srv
ros::ServiceServer _get_state_srv
ros::ServiceServer _get_voltage_srv
t_ljdata _labjack_data
LabjackDriverInterface * _ljdriver
ros::NodeHandle _nh
ros::NodeHandle _nh_private
ros::Rate _publish_rate
ros::ServiceServer _set_state_srv
ros::ServiceServer _touch_srv

Detailed Description

Definition at line 40 of file labjack_node.h.


Constructor & Destructor Documentation

LabjackNode::LabjackNode ( LabjackDriverInterface *  ljdriver)

Empty constructor.

Definition at line 30 of file labjack_node.cpp.

Destructor.

Definition at line 56 of file labjack_node.cpp.


Member Function Documentation

int LabjackNode::clearStateD ( long  stateD)

Function which assign a value of 0 to the D line specified in the parameter.

Parameters:
stateDthe state of the line to clear.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 270 of file labjack_node.cpp.

int LabjackNode::clearStateIO ( long  stateIO)

Function which clear the state of one IO line.

Parameters:
stateIOthe state of the line to clear.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 368 of file labjack_node.cpp.

Function which clear the watchog.

Returns:
return 0 if no error, other thing if something happen.

Definition at line 620 of file labjack_node.cpp.

int LabjackNode::enableBase ( bool  enable)

Function which enable the base to move.

Parameters:
enabletrue or false depending on the case.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 582 of file labjack_node.cpp.

int LabjackNode::enableBody ( bool  enable)

Function which enable the body to move.

Parameters:
enabletrue or false depending on the case.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 594 of file labjack_node.cpp.

float LabjackNode::getAI ( long  channel)

Function which get the value of one AI line.

Parameters:
channelthe channel of the line to clear.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 422 of file labjack_node.cpp.

Function which get the value of the AI lines.

Returns:
return 0 if no error, other thing if something happen.

Definition at line 379 of file labjack_node.cpp.

Function which return all data relative to the labjack. Digital and analog lines. These lines have connected: touch sensors, batteries, state of the emergency button RF, state of the emergency button of Maggie, control signal of motor in the base and control signal of the other motors.

Returns:
if no error, return all data, if error, NULL

Definition at line 140 of file labjack_node.cpp.

Function which return the directions of the D lines: 0 is an input and 1 an output.

Returns:
if error, return negative values.

Definition at line 281 of file labjack_node.cpp.

bool LabjackNode::getIsPlugged ( batteries_skill_msgs::LabjackPlugInfo::Request &  req,
batteries_skill_msgs::LabjackPlugInfo::Response &  resp 
)

Callback to get the information of the batteries.

Parameters:
reqLabjackBatteryInfo type request.
respLabjackBatteryInfo type response.
Returns:
true if there are no errors.

Definition at line 107 of file labjack_node.cpp.

bool LabjackNode::getPower ( batteries_skill_msgs::LabjackBatteryInfo::Request &  req,
batteries_skill_msgs::LabjackBatteryInfo::Response &  resp 
)

Callback to get the information of the batteries.

Parameters:
reqLabjackBatteryInfo type request.
respLabjackBatteryInfo type response.
Returns:
true if there are no errors.

Definition at line 97 of file labjack_node.cpp.

Function which get the current state.

Returns:
the current state of the labjack.

Definition at line 508 of file labjack_node.cpp.

int LabjackNode::getStateD ( long  stateD)

Function which return the state of a specific D line.

Parameters:
stateDthe line specified.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 228 of file labjack_node.cpp.

Function which return the state of all D lines.

Returns:
if error, return negative values.

Definition at line 200 of file labjack_node.cpp.

int LabjackNode::getStateIO ( long  stateIO)

Function which get the state of one IO line.

Parameters:
stateIOthe state of the IO line.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 327 of file labjack_node.cpp.

Function which get the state of the IO lines.

Returns:
the state of the IOs.

Definition at line 297 of file labjack_node.cpp.

bool LabjackNode::getStates ( basic_states_skill_msgs::GetLabjackState::Request &  req,
basic_states_skill_msgs::GetLabjackState::Response &  resp 
)

Callback to get the information of the states.

Parameters:
reqGetLabjackState type request.
respGetLabjackState type response.
Returns:
true if there are no errors.

Definition at line 117 of file labjack_node.cpp.

Function which get the value of the touch sensors.

Returns:
the current value of the touch sensors.

Definition at line 704 of file labjack_node.cpp.

bool LabjackNode::getTouchSensors ( touch_skill_msgs::LabjackTouchInfo::Request &  req,
touch_skill_msgs::LabjackTouchInfo::Response &  resp 
)

Callback to get the information of the touch sensors.

Parameters:
reqLabjackTouchInfo type request.
respLabjackTouchInfo type response.
Returns:
true if there are no errors.

Definition at line 83 of file labjack_node.cpp.

Function which return the value in volts of the battery.

Returns:
the voltage of the battery.

Definition at line 664 of file labjack_node.cpp.

Initialize the labjack node.

Definition at line 62 of file labjack_node.cpp.

Function which get if the labjack is in emergency state.

Returns:
true or false depending on the state of the IO line.

Definition at line 631 of file labjack_node.cpp.

Function which return the state of the robot connection.

Returns:
true if robot is plugged, false in other case.

Definition at line 684 of file labjack_node.cpp.

Publish information from the battery.

Publish information from the states.

Publish information from the touch sensors.

int LabjackNode::setAOs ( float2  voltageAO)

Function which assign a voltage. If only one parameter desire, pass negative value to the other.

Parameters:
voltageAOthe voltage to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 443 of file labjack_node.cpp.

Function which emergency by software.

Returns:
return 0 if no error, other thing if something happen.

Definition at line 643 of file labjack_node.cpp.

Function which write a pulse in a D line.

Parameters:
datathe data to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 454 of file labjack_node.cpp.

Function which write a pulse in a IO line.

Parameters:
datathe data to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 481 of file labjack_node.cpp.

int LabjackNode::setState ( int  state)

Function which set the state.

Parameters:
statethe new state.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 537 of file labjack_node.cpp.

int LabjackNode::setStateD ( long  stateD)

Function which assign a value of 1 to the D line specified in the parameter.

Parameters:
stateDthe state of the line to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 258 of file labjack_node.cpp.

int LabjackNode::setStateDs ( long  stateD)

Function which assing a new state to all D lines.

Parameters:
stateDnew state to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 215 of file labjack_node.cpp.

int LabjackNode::setStateIO ( long  stateIO)

Function which set the state of one IO line.

Parameters:
stateIOthe of the line to set.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 357 of file labjack_node.cpp.

int LabjackNode::setStateIOs ( long  stateIO)

Function which set the state of the IO lines.

Parameters:
stateIOthe new state of IO line.
Returns:
return 0 if no error, other thing if something happen.

Definition at line 313 of file labjack_node.cpp.

bool LabjackNode::setStates ( basic_states_skill_msgs::SetLabjackState::Request &  req,
basic_states_skill_msgs::SetLabjackState::Response &  resp 
)

Callback to set a state.

Parameters:
reqSetLabjackState type request.
respSetLabjackState type response.
Returns:
true if there are no errors.

Definition at line 127 of file labjack_node.cpp.

Function which set the watchdog.

Returns:
return 0 if no error, other thing if something happen.

Definition at line 606 of file labjack_node.cpp.

Spin the node.

Definition at line 73 of file labjack_node.cpp.


Member Data Documentation

Definition at line 334 of file labjack_node.h.

Definition at line 335 of file labjack_node.h.

Definition at line 333 of file labjack_node.h.

Definition at line 341 of file labjack_node.h.

LabjackDriverInterface* LabjackNode::_ljdriver [private]

Definition at line 342 of file labjack_node.h.

Definition at line 328 of file labjack_node.h.

Definition at line 329 of file labjack_node.h.

Definition at line 339 of file labjack_node.h.

Definition at line 336 of file labjack_node.h.

Definition at line 332 of file labjack_node.h.


The documentation for this class was generated from the following files:


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