#include <cyberglove_publisher.h>
Public Member Functions | |
CyberglovePublisher () | |
Constructor. | |
void | initialize_calibration (std::string path_to_calibration) |
bool | isPublishing () |
void | setPublishing (bool value) |
~CyberglovePublisher () | |
Destructor. | |
Public Attributes | |
Publisher | cyberglove_pub |
Private Member Functions | |
void | add_jointstate (float position, std::string joint_name) |
void | glove_callback (std::vector< float > glove_pos, bool light_on) |
Private Attributes | |
xml_calibration_parser::XmlCalibrationParser | calibration_parser |
the calibration parser | |
std::vector< float > | calibration_values |
Publisher | cyberglove_raw_pub |
std::vector< std::vector< float > > | glove_positions |
sensor_msgs::JointState | jointstate_msg |
sensor_msgs::JointState | jointstate_raw_msg |
NodeHandle | n_tilde |
NodeHandle | node |
std::string | path_to_glove |
unsigned int | publish_counter_index |
unsigned int | publish_counter_max |
bool | publishing |
Rate | sampling_rate |
boost::shared_ptr < CybergloveSerial > | serial_glove |
the actual connection with the cyberglove is done here. |
Definition at line 48 of file cyberglove_publisher.h.
Constructor.
Definition at line 47 of file cyberglove_publisher.cpp.
Destructor.
Definition at line 148 of file cyberglove_publisher.cpp.
void cyberglove::CyberglovePublisher::add_jointstate | ( | float | position, |
std::string | joint_name | ||
) | [private] |
Definition at line 230 of file cyberglove_publisher.cpp.
void cyberglove::CyberglovePublisher::glove_callback | ( | std::vector< float > | glove_pos, |
bool | light_on | ||
) | [private] |
The callback function: called each time a full message is received. This function is bound to the serial_glove object using boost::bind.
glove_pos | A vector containing the current raw joints positions. |
light_on | true if the light is on, false otherwise. |
Definition at line 177 of file cyberglove_publisher.cpp.
void cyberglove::CyberglovePublisher::initialize_calibration | ( | std::string | path_to_calibration | ) |
Definition at line 152 of file cyberglove_publisher.cpp.
Definition at line 157 of file cyberglove_publisher.cpp.
void cyberglove::CyberglovePublisher::setPublishing | ( | bool | value | ) |
Definition at line 169 of file cyberglove_publisher.cpp.
xml_calibration_parser::XmlCalibrationParser cyberglove::CyberglovePublisher::calibration_parser [private] |
the calibration parser
Definition at line 88 of file cyberglove_publisher.h.
std::vector<float> cyberglove::CyberglovePublisher::calibration_values [private] |
Definition at line 97 of file cyberglove_publisher.h.
Definition at line 57 of file cyberglove_publisher.h.
Definition at line 90 of file cyberglove_publisher.h.
std::vector<std::vector<float> > cyberglove::CyberglovePublisher::glove_positions [private] |
Definition at line 99 of file cyberglove_publisher.h.
sensor_msgs::JointState cyberglove::CyberglovePublisher::jointstate_msg [private] |
Definition at line 92 of file cyberglove_publisher.h.
sensor_msgs::JointState cyberglove::CyberglovePublisher::jointstate_raw_msg [private] |
Definition at line 93 of file cyberglove_publisher.h.
Definition at line 67 of file cyberglove_publisher.h.
Definition at line 67 of file cyberglove_publisher.h.
std::string cyberglove::CyberglovePublisher::path_to_glove [private] |
Definition at line 84 of file cyberglove_publisher.h.
unsigned int cyberglove::CyberglovePublisher::publish_counter_index [private] |
Definition at line 69 of file cyberglove_publisher.h.
unsigned int cyberglove::CyberglovePublisher::publish_counter_max [private] |
Definition at line 69 of file cyberglove_publisher.h.
Definition at line 85 of file cyberglove_publisher.h.
Definition at line 68 of file cyberglove_publisher.h.
boost::shared_ptr<CybergloveSerial> cyberglove::CyberglovePublisher::serial_glove [private] |
the actual connection with the cyberglove is done here.
Definition at line 72 of file cyberglove_publisher.h.