#include <rotunit.h>
| Public Member Functions | |
| int | can_read_fifo () | 
| void | can_rotunit (const can_frame &frame) | 
| void | can_rotunit_send (double speed) | 
| Rotunit (ros::NodeHandle &nh) | |
| void | rotunitCallback (const geometry_msgs::Twist::ConstPtr &msg) | 
| bool | rotunitRotVelSrv (uos_rotunit_driver::RotVelSrv::Request &req, uos_rotunit_driver::RotVelSrv::Response &res) | 
| ~Rotunit () | |
| Private Member Functions | |
| double | normalize2PI (double angle) | 
| Private Attributes | |
| CAN | can_ | 
| ros::NodeHandle | nh_ | 
| sensor_msgs::JointState | previous_state | 
| ros::Publisher | rot_pub_ | 
| ros::ServiceServer | rot_vel_srv_ | 
| ros::Subscriber | sub_ | 
| ros::Publisher | vel_pub_ | 
| Rotunit::Rotunit | ( | ros::NodeHandle & | nh | ) | 
Definition at line 3 of file rotunit.cpp.
Definition at line 15 of file rotunit.cpp.
| int Rotunit::can_read_fifo | ( | ) | 
Definition at line 92 of file rotunit.cpp.
| void Rotunit::can_rotunit | ( | const can_frame & | frame | ) | 
Definition at line 61 of file rotunit.cpp.
| void Rotunit::can_rotunit_send | ( | double | speed | ) | 
Definition at line 20 of file rotunit.cpp.
| double Rotunit::normalize2PI | ( | double | angle | ) |  [private] | 
Definition at line 39 of file rotunit.cpp.
| void Rotunit::rotunitCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) | 
Definition at line 56 of file rotunit.cpp.
| bool Rotunit::rotunitRotVelSrv | ( | uos_rotunit_driver::RotVelSrv::Request & | req, | 
| uos_rotunit_driver::RotVelSrv::Response & | res | ||
| ) | 
Definition at line 49 of file rotunit.cpp.
| CAN Rotunit::can_  [private] | 
| ros::NodeHandle Rotunit::nh_  [private] | 
| sensor_msgs::JointState Rotunit::previous_state  [private] | 
| ros::Publisher Rotunit::rot_pub_  [private] | 
| ros::ServiceServer Rotunit::rot_vel_srv_  [private] | 
| ros::Subscriber Rotunit::sub_  [private] | 
| ros::Publisher Rotunit::vel_pub_  [private] |