#include <eyelids_node.h>
Public Member Functions | |
| EyelidsNode (SerialCommunicationInterface *serial_comm) | |
| Parameterized constructor. | |
| void | init () |
| Initialize the eyelids node. | |
| int | move (int position) |
| Method to move the servomotors. | |
| bool | move_abs_pos (motor_controller_msgs::MoveAbsPos::Request &req, motor_controller_msgs::MoveAbsPos::Response &resp) |
| Callback to move motors by absolute position. | |
| bool | move_str_pos (eyelids_msgs::MoveStrPos::Request &req, eyelids_msgs::MoveStrPos::Response &resp) |
| Callback to move motors by string name position. | |
| void | spin () |
| Spin the node. | |
| ~EyelidsNode () | |
| Destructor. | |
Private Attributes | |
| ros::Publisher | _get_position_msg |
| ros::ServiceServer | _move_abs_pos_srv |
| ros::ServiceServer | _move_str_pos_srv |
| ros::NodeHandle | _nh |
| ros::NodeHandle | _nh_private |
| struct termios | _oldtio |
| ros::Rate | _publish_rate |
| SerialCommunicationInterface * | _serial_comm |
| std::string | _side |
Definition at line 37 of file eyelids_node.h.
| EyelidsNode::EyelidsNode | ( | SerialCommunicationInterface * | serial_comm | ) |
Parameterized constructor.
| serial_comm,the | driver interface. |
Definition at line 28 of file eyelids_node.cpp.
Destructor.
Definition at line 61 of file eyelids_node.cpp.
| void EyelidsNode::init | ( | ) |
| int EyelidsNode::move | ( | int | position | ) |
Method to move the servomotors.
| position,absolute | position with values in the range between 0 and 254. |
Definition at line 142 of file eyelids_node.cpp.
| bool EyelidsNode::move_abs_pos | ( | motor_controller_msgs::MoveAbsPos::Request & | req, |
| motor_controller_msgs::MoveAbsPos::Response & | resp | ||
| ) |
Callback to move motors by absolute position.
| req | MoveAbsPos type request. |
| resp | MoveAbsPos type response. |
Definition at line 94 of file eyelids_node.cpp.
| bool EyelidsNode::move_str_pos | ( | eyelids_msgs::MoveStrPos::Request & | req, |
| eyelids_msgs::MoveStrPos::Response & | resp | ||
| ) |
Callback to move motors by string name position.
| req | MoveStrPos type request. |
| resp | MoveStrPos type response. |
Definition at line 106 of file eyelids_node.cpp.
| void EyelidsNode::spin | ( | ) |
ros::Publisher EyelidsNode::_get_position_msg [private] |
Definition at line 101 of file eyelids_node.h.
Definition at line 104 of file eyelids_node.h.
Definition at line 105 of file eyelids_node.h.
ros::NodeHandle EyelidsNode::_nh [private] |
Definition at line 97 of file eyelids_node.h.
ros::NodeHandle EyelidsNode::_nh_private [private] |
Definition at line 98 of file eyelids_node.h.
struct termios EyelidsNode::_oldtio [private] |
Definition at line 112 of file eyelids_node.h.
ros::Rate EyelidsNode::_publish_rate [private] |
Definition at line 108 of file eyelids_node.h.
SerialCommunicationInterface* EyelidsNode::_serial_comm [private] |
Definition at line 111 of file eyelids_node.h.
std::string EyelidsNode::_side [private] |
Definition at line 115 of file eyelids_node.h.